1#![doc = "MAVLink uAvionix dialect."]
2#![doc = ""]
3#![doc = "This file was automatically generated, do not edit."]
4#[cfg(feature = "arbitrary")]
5use arbitrary::Arbitrary;
6#[allow(unused_imports)]
7use bitflags::bitflags;
8use mavlink_core::{bytes::Bytes, bytes_mut::BytesMut, MavlinkVersion, Message, MessageData};
9#[allow(unused_imports)]
10use num_derive::FromPrimitive;
11#[allow(unused_imports)]
12use num_derive::ToPrimitive;
13#[allow(unused_imports)]
14use num_traits::FromPrimitive;
15#[allow(unused_imports)]
16use num_traits::ToPrimitive;
17#[cfg(feature = "serde")]
18use serde::{Deserialize, Serialize};
19#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
20#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21#[cfg_attr(feature = "serde", serde(tag = "type"))]
22#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23#[repr(u32)]
24#[doc = "Parachute actions. Trigger release and enable/disable auto-release."]
25pub enum ParachuteAction {
26 #[doc = "Disable auto-release of parachute (i.e. release triggered by crash detectors)."]
27 PARACHUTE_DISABLE = 0,
28 #[doc = "Enable auto-release of parachute."]
29 PARACHUTE_ENABLE = 1,
30 #[doc = "Release parachute and kill motors."]
31 PARACHUTE_RELEASE = 2,
32}
33impl ParachuteAction {
34 pub const DEFAULT: Self = Self::PARACHUTE_DISABLE;
35}
36impl Default for ParachuteAction {
37 fn default() -> Self {
38 Self::DEFAULT
39 }
40}
41bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags."] pub struct GimbalManagerCapFlags : u32 { # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT = 1 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL = 2 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS = 4 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK = 16 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS = 32 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK = 128 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS = 256 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW = 512 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK = 1024 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW."] const GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = 4096 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS = 8192 ; # [doc = "Gimbal manager supports to point to a local position."] const GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL = 65536 ; # [doc = "Gimbal manager supports to point to a global latitude, longitude, altitude position."] const GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL = 131072 ; } }
42impl GimbalManagerCapFlags {
43 pub const DEFAULT: Self = Self::GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT;
44}
45impl Default for GimbalManagerCapFlags {
46 fn default() -> Self {
47 Self::DEFAULT
48 }
49}
50#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
51#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
52#[cfg_attr(feature = "serde", serde(tag = "type"))]
53#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
54#[repr(u32)]
55pub enum MagCalStatus {
56 MAG_CAL_NOT_STARTED = 0,
57 MAG_CAL_WAITING_TO_START = 1,
58 MAG_CAL_RUNNING_STEP_ONE = 2,
59 MAG_CAL_RUNNING_STEP_TWO = 3,
60 MAG_CAL_SUCCESS = 4,
61 MAG_CAL_FAILED = 5,
62 MAG_CAL_BAD_ORIENTATION = 6,
63 MAG_CAL_BAD_RADIUS = 7,
64}
65impl MagCalStatus {
66 pub const DEFAULT: Self = Self::MAG_CAL_NOT_STARTED;
67}
68impl Default for MagCalStatus {
69 fn default() -> Self {
70 Self::DEFAULT
71 }
72}
73#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
74#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
75#[cfg_attr(feature = "serde", serde(tag = "type"))]
76#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
77#[repr(u32)]
78pub enum NavVtolLandOptions {
79 #[doc = "Default autopilot landing behaviour."]
80 NAV_VTOL_LAND_OPTIONS_DEFAULT = 0,
81 #[doc = "Descend in fixed wing mode, transitioning to multicopter mode for vertical landing when close to the ground. The fixed wing descent pattern is at the discretion of the vehicle (e.g. transition altitude, loiter direction, radius, and speed, etc.)."]
82 NAV_VTOL_LAND_OPTIONS_FW_DESCENT = 1,
83 #[doc = "Land in multicopter mode on reaching the landing coordinates (the whole landing is by \"hover descent\")."]
84 NAV_VTOL_LAND_OPTIONS_HOVER_DESCENT = 2,
85}
86impl NavVtolLandOptions {
87 pub const DEFAULT: Self = Self::NAV_VTOL_LAND_OPTIONS_DEFAULT;
88}
89impl Default for NavVtolLandOptions {
90 fn default() -> Self {
91 Self::DEFAULT
92 }
93}
94#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
95#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
96#[cfg_attr(feature = "serde", serde(tag = "type"))]
97#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
98#[repr(u32)]
99pub enum MavlinkDataStreamType {
100 MAVLINK_DATA_STREAM_IMG_JPEG = 0,
101 MAVLINK_DATA_STREAM_IMG_BMP = 1,
102 MAVLINK_DATA_STREAM_IMG_RAW8U = 2,
103 MAVLINK_DATA_STREAM_IMG_RAW32U = 3,
104 MAVLINK_DATA_STREAM_IMG_PGM = 4,
105 MAVLINK_DATA_STREAM_IMG_PNG = 5,
106}
107impl MavlinkDataStreamType {
108 pub const DEFAULT: Self = Self::MAVLINK_DATA_STREAM_IMG_JPEG;
109}
110impl Default for MavlinkDataStreamType {
111 fn default() -> Self {
112 Self::DEFAULT
113 }
114}
115#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
116#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
117#[cfg_attr(feature = "serde", serde(tag = "type"))]
118#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
119#[repr(u32)]
120#[doc = "State flags for ADS-B transponder status report"]
121pub enum UavionixAdsbOutStatusNicNacp {
122 UAVIONIX_ADSB_NIC_CR_20_NM = 1,
123 UAVIONIX_ADSB_NIC_CR_8_NM = 2,
124 UAVIONIX_ADSB_NIC_CR_4_NM = 3,
125 UAVIONIX_ADSB_NIC_CR_2_NM = 4,
126 UAVIONIX_ADSB_NIC_CR_1_NM = 5,
127 UAVIONIX_ADSB_NIC_CR_0_3_NM = 6,
128 UAVIONIX_ADSB_NIC_CR_0_2_NM = 7,
129 UAVIONIX_ADSB_NIC_CR_0_1_NM = 8,
130 UAVIONIX_ADSB_NIC_CR_75_M = 9,
131 UAVIONIX_ADSB_NIC_CR_25_M = 10,
132 UAVIONIX_ADSB_NIC_CR_7_5_M = 11,
133 UAVIONIX_ADSB_NACP_EPU_10_NM = 16,
134 UAVIONIX_ADSB_NACP_EPU_4_NM = 32,
135 UAVIONIX_ADSB_NACP_EPU_2_NM = 48,
136 UAVIONIX_ADSB_NACP_EPU_1_NM = 64,
137 UAVIONIX_ADSB_NACP_EPU_0_5_NM = 80,
138 UAVIONIX_ADSB_NACP_EPU_0_3_NM = 96,
139 UAVIONIX_ADSB_NACP_EPU_0_1_NM = 112,
140 UAVIONIX_ADSB_NACP_EPU_0_05_NM = 128,
141 UAVIONIX_ADSB_NACP_EPU_30_M = 144,
142 UAVIONIX_ADSB_NACP_EPU_10_M = 160,
143 UAVIONIX_ADSB_NACP_EPU_3_M = 176,
144}
145impl UavionixAdsbOutStatusNicNacp {
146 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_NIC_CR_20_NM;
147}
148impl Default for UavionixAdsbOutStatusNicNacp {
149 fn default() -> Self {
150 Self::DEFAULT
151 }
152}
153#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
154#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
155#[cfg_attr(feature = "serde", serde(tag = "type"))]
156#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
157#[repr(u32)]
158#[doc = "SERIAL_CONTROL device types"]
159pub enum SerialControlDev {
160 #[doc = "First telemetry port"]
161 SERIAL_CONTROL_DEV_TELEM1 = 0,
162 #[doc = "Second telemetry port"]
163 SERIAL_CONTROL_DEV_TELEM2 = 1,
164 #[doc = "First GPS port"]
165 SERIAL_CONTROL_DEV_GPS1 = 2,
166 #[doc = "Second GPS port"]
167 SERIAL_CONTROL_DEV_GPS2 = 3,
168 #[doc = "system shell"]
169 SERIAL_CONTROL_DEV_SHELL = 10,
170 #[doc = "SERIAL0"]
171 SERIAL_CONTROL_SERIAL0 = 100,
172 #[doc = "SERIAL1"]
173 SERIAL_CONTROL_SERIAL1 = 101,
174 #[doc = "SERIAL2"]
175 SERIAL_CONTROL_SERIAL2 = 102,
176 #[doc = "SERIAL3"]
177 SERIAL_CONTROL_SERIAL3 = 103,
178 #[doc = "SERIAL4"]
179 SERIAL_CONTROL_SERIAL4 = 104,
180 #[doc = "SERIAL5"]
181 SERIAL_CONTROL_SERIAL5 = 105,
182 #[doc = "SERIAL6"]
183 SERIAL_CONTROL_SERIAL6 = 106,
184 #[doc = "SERIAL7"]
185 SERIAL_CONTROL_SERIAL7 = 107,
186 #[doc = "SERIAL8"]
187 SERIAL_CONTROL_SERIAL8 = 108,
188 #[doc = "SERIAL9"]
189 SERIAL_CONTROL_SERIAL9 = 109,
190}
191impl SerialControlDev {
192 pub const DEFAULT: Self = Self::SERIAL_CONTROL_DEV_TELEM1;
193}
194impl Default for SerialControlDev {
195 fn default() -> Self {
196 Self::DEFAULT
197 }
198}
199#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
200#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
201#[cfg_attr(feature = "serde", serde(tag = "type"))]
202#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
203#[repr(u32)]
204#[doc = "These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65."]
205pub enum FirmwareVersionType {
206 #[doc = "development release"]
207 FIRMWARE_VERSION_TYPE_DEV = 0,
208 #[doc = "alpha release"]
209 FIRMWARE_VERSION_TYPE_ALPHA = 64,
210 #[doc = "beta release"]
211 FIRMWARE_VERSION_TYPE_BETA = 128,
212 #[doc = "release candidate"]
213 FIRMWARE_VERSION_TYPE_RC = 192,
214 #[doc = "official stable release"]
215 FIRMWARE_VERSION_TYPE_OFFICIAL = 255,
216}
217impl FirmwareVersionType {
218 pub const DEFAULT: Self = Self::FIRMWARE_VERSION_TYPE_DEV;
219}
220impl Default for FirmwareVersionType {
221 fn default() -> Self {
222 Self::DEFAULT
223 }
224}
225#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
226#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
227#[cfg_attr(feature = "serde", serde(tag = "type"))]
228#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
229#[repr(u32)]
230pub enum MavOdidOperatorLocationType {
231 #[doc = "The location/altitude of the operator is the same as the take-off location."]
232 MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF = 0,
233 #[doc = "The location/altitude of the operator is dynamic. E.g. based on live GNSS data."]
234 MAV_ODID_OPERATOR_LOCATION_TYPE_LIVE_GNSS = 1,
235 #[doc = "The location/altitude of the operator are fixed values."]
236 MAV_ODID_OPERATOR_LOCATION_TYPE_FIXED = 2,
237}
238impl MavOdidOperatorLocationType {
239 pub const DEFAULT: Self = Self::MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF;
240}
241impl Default for MavOdidOperatorLocationType {
242 fn default() -> Self {
243 Self::DEFAULT
244 }
245}
246bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for ADS-B transponder status report"] pub struct UavionixAdsbOutStatusState : u8 { const UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND = 1 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_INTERROGATED_SINCE_LAST = 2 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED = 4 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE = 8 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED = 16 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED = 32 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED = 64 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED = 128 ; } }
247impl UavionixAdsbOutStatusState {
248 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND;
249}
250impl Default for UavionixAdsbOutStatusState {
251 fn default() -> Self {
252 Self::DEFAULT
253 }
254}
255#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
256#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
257#[cfg_attr(feature = "serde", serde(tag = "type"))]
258#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
259#[repr(u32)]
260#[doc = "Enumeration of estimator types"]
261pub enum MavEstimatorType {
262 #[doc = "Unknown type of the estimator."]
263 MAV_ESTIMATOR_TYPE_UNKNOWN = 0,
264 #[doc = "This is a naive estimator without any real covariance feedback."]
265 MAV_ESTIMATOR_TYPE_NAIVE = 1,
266 #[doc = "Computer vision based estimate. Might be up to scale."]
267 MAV_ESTIMATOR_TYPE_VISION = 2,
268 #[doc = "Visual-inertial estimate."]
269 MAV_ESTIMATOR_TYPE_VIO = 3,
270 #[doc = "Plain GPS estimate."]
271 MAV_ESTIMATOR_TYPE_GPS = 4,
272 #[doc = "Estimator integrating GPS and inertial sensing."]
273 MAV_ESTIMATOR_TYPE_GPS_INS = 5,
274 #[doc = "Estimate from external motion capturing system."]
275 MAV_ESTIMATOR_TYPE_MOCAP = 6,
276 #[doc = "Estimator based on lidar sensor input."]
277 MAV_ESTIMATOR_TYPE_LIDAR = 7,
278 #[doc = "Estimator on autopilot."]
279 MAV_ESTIMATOR_TYPE_AUTOPILOT = 8,
280}
281impl MavEstimatorType {
282 pub const DEFAULT: Self = Self::MAV_ESTIMATOR_TYPE_UNKNOWN;
283}
284impl Default for MavEstimatorType {
285 fn default() -> Self {
286 Self::DEFAULT
287 }
288}
289#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
290#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
291#[cfg_attr(feature = "serde", serde(tag = "type"))]
292#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
293#[repr(u32)]
294#[doc = "Camera tracking status flags"]
295pub enum CameraTrackingStatusFlags {
296 #[doc = "Camera is not tracking"]
297 CAMERA_TRACKING_STATUS_FLAGS_IDLE = 0,
298 #[doc = "Camera is tracking"]
299 CAMERA_TRACKING_STATUS_FLAGS_ACTIVE = 1,
300 #[doc = "Camera tracking in error state"]
301 CAMERA_TRACKING_STATUS_FLAGS_ERROR = 2,
302}
303impl CameraTrackingStatusFlags {
304 pub const DEFAULT: Self = Self::CAMERA_TRACKING_STATUS_FLAGS_IDLE;
305}
306impl Default for CameraTrackingStatusFlags {
307 fn default() -> Self {
308 Self::DEFAULT
309 }
310}
311bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Transceiver RF control flags for ADS-B transponder dynamic reports"] pub struct UavionixAdsbOutRfSelect : u8 { const UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED = 1 ; const UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED = 2 ; } }
312impl UavionixAdsbOutRfSelect {
313 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED;
314}
315impl Default for UavionixAdsbOutRfSelect {
316 fn default() -> Self {
317 Self::DEFAULT
318 }
319}
320#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
321#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
322#[cfg_attr(feature = "serde", serde(tag = "type"))]
323#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
324#[repr(u32)]
325pub enum FenceBreach {
326 #[doc = "No last fence breach"]
327 FENCE_BREACH_NONE = 0,
328 #[doc = "Breached minimum altitude"]
329 FENCE_BREACH_MINALT = 1,
330 #[doc = "Breached maximum altitude"]
331 FENCE_BREACH_MAXALT = 2,
332 #[doc = "Breached fence boundary"]
333 FENCE_BREACH_BOUNDARY = 3,
334}
335impl FenceBreach {
336 pub const DEFAULT: Self = Self::FENCE_BREACH_NONE;
337}
338impl Default for FenceBreach {
339 fn default() -> Self {
340 Self::DEFAULT
341 }
342}
343#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
344#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
345#[cfg_attr(feature = "serde", serde(tag = "type"))]
346#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
347#[repr(u32)]
348pub enum MavOdidAuthType {
349 #[doc = "No authentication type is specified."]
350 MAV_ODID_AUTH_TYPE_NONE = 0,
351 #[doc = "Signature for the UAS (Unmanned Aircraft System) ID."]
352 MAV_ODID_AUTH_TYPE_UAS_ID_SIGNATURE = 1,
353 #[doc = "Signature for the Operator ID."]
354 MAV_ODID_AUTH_TYPE_OPERATOR_ID_SIGNATURE = 2,
355 #[doc = "Signature for the entire message set."]
356 MAV_ODID_AUTH_TYPE_MESSAGE_SET_SIGNATURE = 3,
357 #[doc = "Authentication is provided by Network Remote ID."]
358 MAV_ODID_AUTH_TYPE_NETWORK_REMOTE_ID = 4,
359 #[doc = "The exact authentication type is indicated by the first byte of authentication_data and these type values are managed by ICAO."]
360 MAV_ODID_AUTH_TYPE_SPECIFIC_AUTHENTICATION = 5,
361}
362impl MavOdidAuthType {
363 pub const DEFAULT: Self = Self::MAV_ODID_AUTH_TYPE_NONE;
364}
365impl Default for MavOdidAuthType {
366 fn default() -> Self {
367 Self::DEFAULT
368 }
369}
370bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Mode properties."] pub struct MavModeProperty : u32 { # [doc = "If set, this mode is an advanced mode. For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not. A GCS can optionally use this flag to configure the UI for its intended users."] const MAV_MODE_PROPERTY_ADVANCED = 1 ; # [doc = "If set, this mode should not be added to the list of selectable modes. The mode might still be selected by the FC directly (for example as part of a failsafe)."] const MAV_MODE_PROPERTY_NOT_USER_SELECTABLE = 2 ; # [doc = "If set, this mode is automatically controlled (it may use but does not require a manual controller). If unset the mode is a assumed to require user input (be a manual mode)."] const MAV_MODE_PROPERTY_AUTO_MODE = 4 ; } }
371impl MavModeProperty {
372 pub const DEFAULT: Self = Self::MAV_MODE_PROPERTY_ADVANCED;
373}
374impl Default for MavModeProperty {
375 fn default() -> Self {
376 Self::DEFAULT
377 }
378}
379bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in ESTIMATOR_STATUS message"] pub struct EstimatorStatusFlags : u16 { # [doc = "True if the attitude estimate is good"] const ESTIMATOR_ATTITUDE = 1 ; # [doc = "True if the horizontal velocity estimate is good"] const ESTIMATOR_VELOCITY_HORIZ = 2 ; # [doc = "True if the vertical velocity estimate is good"] const ESTIMATOR_VELOCITY_VERT = 4 ; # [doc = "True if the horizontal position (relative) estimate is good"] const ESTIMATOR_POS_HORIZ_REL = 8 ; # [doc = "True if the horizontal position (absolute) estimate is good"] const ESTIMATOR_POS_HORIZ_ABS = 16 ; # [doc = "True if the vertical position (absolute) estimate is good"] const ESTIMATOR_POS_VERT_ABS = 32 ; # [doc = "True if the vertical position (above ground) estimate is good"] const ESTIMATOR_POS_VERT_AGL = 64 ; # [doc = "True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)"] const ESTIMATOR_CONST_POS_MODE = 128 ; # [doc = "True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate"] const ESTIMATOR_PRED_POS_HORIZ_REL = 256 ; # [doc = "True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate"] const ESTIMATOR_PRED_POS_HORIZ_ABS = 512 ; # [doc = "True if the EKF has detected a GPS glitch"] const ESTIMATOR_GPS_GLITCH = 1024 ; # [doc = "True if the EKF has detected bad accelerometer data"] const ESTIMATOR_ACCEL_ERROR = 2048 ; } }
380impl EstimatorStatusFlags {
381 pub const DEFAULT: Self = Self::ESTIMATOR_ATTITUDE;
382}
383impl Default for EstimatorStatusFlags {
384 fn default() -> Self {
385 Self::DEFAULT
386 }
387}
388#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
389#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
390#[cfg_attr(feature = "serde", serde(tag = "type"))]
391#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
392#[repr(u32)]
393#[doc = "The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI)."]
394pub enum MavRoi {
395 #[doc = "No region of interest."]
396 MAV_ROI_NONE = 0,
397 #[doc = "Point toward next waypoint, with optional pitch/roll/yaw offset."]
398 MAV_ROI_WPNEXT = 1,
399 #[doc = "Point toward given waypoint."]
400 MAV_ROI_WPINDEX = 2,
401 #[doc = "Point toward fixed location."]
402 MAV_ROI_LOCATION = 3,
403 #[doc = "Point toward of given id."]
404 MAV_ROI_TARGET = 4,
405}
406impl MavRoi {
407 pub const DEFAULT: Self = Self::MAV_ROI_NONE;
408}
409impl Default for MavRoi {
410 fn default() -> Self {
411 Self::DEFAULT
412 }
413}
414#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
415#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
416#[cfg_attr(feature = "serde", serde(tag = "type"))]
417#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
418#[repr(u32)]
419#[doc = "Actuator output function. Values greater or equal to 1000 are autopilot-specific."]
420pub enum ActuatorOutputFunction {
421 #[doc = "No function (disabled)."]
422 ACTUATOR_OUTPUT_FUNCTION_NONE = 0,
423 #[doc = "Motor 1"]
424 ACTUATOR_OUTPUT_FUNCTION_MOTOR1 = 1,
425 #[doc = "Motor 2"]
426 ACTUATOR_OUTPUT_FUNCTION_MOTOR2 = 2,
427 #[doc = "Motor 3"]
428 ACTUATOR_OUTPUT_FUNCTION_MOTOR3 = 3,
429 #[doc = "Motor 4"]
430 ACTUATOR_OUTPUT_FUNCTION_MOTOR4 = 4,
431 #[doc = "Motor 5"]
432 ACTUATOR_OUTPUT_FUNCTION_MOTOR5 = 5,
433 #[doc = "Motor 6"]
434 ACTUATOR_OUTPUT_FUNCTION_MOTOR6 = 6,
435 #[doc = "Motor 7"]
436 ACTUATOR_OUTPUT_FUNCTION_MOTOR7 = 7,
437 #[doc = "Motor 8"]
438 ACTUATOR_OUTPUT_FUNCTION_MOTOR8 = 8,
439 #[doc = "Motor 9"]
440 ACTUATOR_OUTPUT_FUNCTION_MOTOR9 = 9,
441 #[doc = "Motor 10"]
442 ACTUATOR_OUTPUT_FUNCTION_MOTOR10 = 10,
443 #[doc = "Motor 11"]
444 ACTUATOR_OUTPUT_FUNCTION_MOTOR11 = 11,
445 #[doc = "Motor 12"]
446 ACTUATOR_OUTPUT_FUNCTION_MOTOR12 = 12,
447 #[doc = "Motor 13"]
448 ACTUATOR_OUTPUT_FUNCTION_MOTOR13 = 13,
449 #[doc = "Motor 14"]
450 ACTUATOR_OUTPUT_FUNCTION_MOTOR14 = 14,
451 #[doc = "Motor 15"]
452 ACTUATOR_OUTPUT_FUNCTION_MOTOR15 = 15,
453 #[doc = "Motor 16"]
454 ACTUATOR_OUTPUT_FUNCTION_MOTOR16 = 16,
455 #[doc = "Servo 1"]
456 ACTUATOR_OUTPUT_FUNCTION_SERVO1 = 33,
457 #[doc = "Servo 2"]
458 ACTUATOR_OUTPUT_FUNCTION_SERVO2 = 34,
459 #[doc = "Servo 3"]
460 ACTUATOR_OUTPUT_FUNCTION_SERVO3 = 35,
461 #[doc = "Servo 4"]
462 ACTUATOR_OUTPUT_FUNCTION_SERVO4 = 36,
463 #[doc = "Servo 5"]
464 ACTUATOR_OUTPUT_FUNCTION_SERVO5 = 37,
465 #[doc = "Servo 6"]
466 ACTUATOR_OUTPUT_FUNCTION_SERVO6 = 38,
467 #[doc = "Servo 7"]
468 ACTUATOR_OUTPUT_FUNCTION_SERVO7 = 39,
469 #[doc = "Servo 8"]
470 ACTUATOR_OUTPUT_FUNCTION_SERVO8 = 40,
471 #[doc = "Servo 9"]
472 ACTUATOR_OUTPUT_FUNCTION_SERVO9 = 41,
473 #[doc = "Servo 10"]
474 ACTUATOR_OUTPUT_FUNCTION_SERVO10 = 42,
475 #[doc = "Servo 11"]
476 ACTUATOR_OUTPUT_FUNCTION_SERVO11 = 43,
477 #[doc = "Servo 12"]
478 ACTUATOR_OUTPUT_FUNCTION_SERVO12 = 44,
479 #[doc = "Servo 13"]
480 ACTUATOR_OUTPUT_FUNCTION_SERVO13 = 45,
481 #[doc = "Servo 14"]
482 ACTUATOR_OUTPUT_FUNCTION_SERVO14 = 46,
483 #[doc = "Servo 15"]
484 ACTUATOR_OUTPUT_FUNCTION_SERVO15 = 47,
485 #[doc = "Servo 16"]
486 ACTUATOR_OUTPUT_FUNCTION_SERVO16 = 48,
487}
488impl ActuatorOutputFunction {
489 pub const DEFAULT: Self = Self::ACTUATOR_OUTPUT_FUNCTION_NONE;
490}
491impl Default for ActuatorOutputFunction {
492 fn default() -> Self {
493 Self::DEFAULT
494 }
495}
496#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
497#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
498#[cfg_attr(feature = "serde", serde(tag = "type"))]
499#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
500#[repr(u32)]
501pub enum MavOdidTimeAcc {
502 #[doc = "The timestamp accuracy is unknown."]
503 MAV_ODID_TIME_ACC_UNKNOWN = 0,
504 #[doc = "The timestamp accuracy is smaller than or equal to 0.1 second."]
505 MAV_ODID_TIME_ACC_0_1_SECOND = 1,
506 #[doc = "The timestamp accuracy is smaller than or equal to 0.2 second."]
507 MAV_ODID_TIME_ACC_0_2_SECOND = 2,
508 #[doc = "The timestamp accuracy is smaller than or equal to 0.3 second."]
509 MAV_ODID_TIME_ACC_0_3_SECOND = 3,
510 #[doc = "The timestamp accuracy is smaller than or equal to 0.4 second."]
511 MAV_ODID_TIME_ACC_0_4_SECOND = 4,
512 #[doc = "The timestamp accuracy is smaller than or equal to 0.5 second."]
513 MAV_ODID_TIME_ACC_0_5_SECOND = 5,
514 #[doc = "The timestamp accuracy is smaller than or equal to 0.6 second."]
515 MAV_ODID_TIME_ACC_0_6_SECOND = 6,
516 #[doc = "The timestamp accuracy is smaller than or equal to 0.7 second."]
517 MAV_ODID_TIME_ACC_0_7_SECOND = 7,
518 #[doc = "The timestamp accuracy is smaller than or equal to 0.8 second."]
519 MAV_ODID_TIME_ACC_0_8_SECOND = 8,
520 #[doc = "The timestamp accuracy is smaller than or equal to 0.9 second."]
521 MAV_ODID_TIME_ACC_0_9_SECOND = 9,
522 #[doc = "The timestamp accuracy is smaller than or equal to 1.0 second."]
523 MAV_ODID_TIME_ACC_1_0_SECOND = 10,
524 #[doc = "The timestamp accuracy is smaller than or equal to 1.1 second."]
525 MAV_ODID_TIME_ACC_1_1_SECOND = 11,
526 #[doc = "The timestamp accuracy is smaller than or equal to 1.2 second."]
527 MAV_ODID_TIME_ACC_1_2_SECOND = 12,
528 #[doc = "The timestamp accuracy is smaller than or equal to 1.3 second."]
529 MAV_ODID_TIME_ACC_1_3_SECOND = 13,
530 #[doc = "The timestamp accuracy is smaller than or equal to 1.4 second."]
531 MAV_ODID_TIME_ACC_1_4_SECOND = 14,
532 #[doc = "The timestamp accuracy is smaller than or equal to 1.5 second."]
533 MAV_ODID_TIME_ACC_1_5_SECOND = 15,
534}
535impl MavOdidTimeAcc {
536 pub const DEFAULT: Self = Self::MAV_ODID_TIME_ACC_UNKNOWN;
537}
538impl Default for MavOdidTimeAcc {
539 fn default() -> Self {
540 Self::DEFAULT
541 }
542}
543#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
544#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
545#[cfg_attr(feature = "serde", serde(tag = "type"))]
546#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
547#[repr(u32)]
548#[doc = "Defines how throttle value is represented in MAV_CMD_DO_MOTOR_TEST."]
549pub enum MotorTestThrottleType {
550 #[doc = "Throttle as a percentage (0 ~ 100)"]
551 MOTOR_TEST_THROTTLE_PERCENT = 0,
552 #[doc = "Throttle as an absolute PWM value (normally in range of 1000~2000)."]
553 MOTOR_TEST_THROTTLE_PWM = 1,
554 #[doc = "Throttle pass-through from pilot's transmitter."]
555 MOTOR_TEST_THROTTLE_PILOT = 2,
556 #[doc = "Per-motor compass calibration test."]
557 MOTOR_TEST_COMPASS_CAL = 3,
558}
559impl MotorTestThrottleType {
560 pub const DEFAULT: Self = Self::MOTOR_TEST_THROTTLE_PERCENT;
561}
562impl Default for MotorTestThrottleType {
563 fn default() -> Self {
564 Self::DEFAULT
565 }
566}
567#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
568#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
569#[cfg_attr(feature = "serde", serde(tag = "type"))]
570#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
571#[repr(u32)]
572#[doc = "Video stream types"]
573pub enum VideoStreamType {
574 #[doc = "Stream is RTSP"]
575 VIDEO_STREAM_TYPE_RTSP = 0,
576 #[doc = "Stream is RTP UDP (URI gives the port number)"]
577 VIDEO_STREAM_TYPE_RTPUDP = 1,
578 #[doc = "Stream is MPEG on TCP"]
579 VIDEO_STREAM_TYPE_TCP_MPEG = 2,
580 #[doc = "Stream is MPEG TS (URI gives the port number)"]
581 VIDEO_STREAM_TYPE_MPEG_TS = 3,
582}
583impl VideoStreamType {
584 pub const DEFAULT: Self = Self::VIDEO_STREAM_TYPE_RTSP;
585}
586impl Default for VideoStreamType {
587 fn default() -> Self {
588 Self::DEFAULT
589 }
590}
591#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
592#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
593#[cfg_attr(feature = "serde", serde(tag = "type"))]
594#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
595#[repr(u32)]
596#[doc = "Standard modes with a well understood meaning across flight stacks and vehicle types. For example, most flight stack have the concept of a \"return\" or \"RTL\" mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. The modes supported by a flight stack can be queried using AVAILABLE_MODES and set using MAV_CMD_DO_SET_STANDARD_MODE. The current mode is streamed in CURRENT_MODE. See <https://mavlink.io/en/services/standard_modes.html>"]
597pub enum MavStandardMode {
598 #[doc = "Non standard mode. This may be used when reporting the mode if the current flight mode is not a standard mode."]
599 MAV_STANDARD_MODE_NON_STANDARD = 0,
600 #[doc = "Position mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces. This mode can only be set by vehicles that can hold a fixed position. Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces. Hybrid MC/FW (\"VTOL\") vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles. Fixed-wing (FW) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
601 MAV_STANDARD_MODE_POSITION_HOLD = 1,
602 #[doc = "Orbit (manual). Position-controlled and stabilized manual mode. The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction. Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated. Flight stacks may support the [MAV_CMD_DO_ORBIT](<https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT>) for changing the orbit parameters. MC and FW vehicles may support this mode. Hybrid MC/FW (\"VTOL\") vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
603 MAV_STANDARD_MODE_ORBIT = 2,
604 #[doc = "Cruise mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces. Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces. Hybrid MC/FW (\"VTOL\") vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles. Multicopter (MC) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
605 MAV_STANDARD_MODE_CRUISE = 3,
606 #[doc = "Altitude hold (manual). Altitude-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their altitude. MC vehicles continue with existing momentum and may move with wind (or other external forces). FW vehicles continue with current heading, but may be moved off-track by wind. Hybrid MC/FW (\"VTOL\") vehicles behave according to their current configuration/mode (FW or MC). Other vehicle types must not support this mode (this may be revisited through the PR process)."]
607 MAV_STANDARD_MODE_ALTITUDE_HOLD = 4,
608 #[doc = "Safe recovery mode (auto). Automatic mode that takes vehicle to a predefined safe location via a safe flight path, and may also automatically land the vehicle. This mode is more commonly referred to as RTL and/or or Smart RTL. The precise return location, flight path, and landing behaviour depend on vehicle configuration and type. For example, the vehicle might return to the home/launch location, a rally point, or the start of a mission landing, it might follow a direct path, mission path, or breadcrumb path, and land using a mission landing pattern or some other kind of descent."]
609 MAV_STANDARD_MODE_SAFE_RECOVERY = 5,
610 #[doc = "Mission mode (automatic). Automatic mode that executes MAVLink missions. Missions are executed from the current waypoint as soon as the mode is enabled."]
611 MAV_STANDARD_MODE_MISSION = 6,
612 #[doc = "Land mode (auto). Automatic mode that lands the vehicle at the current location. The precise landing behaviour depends on vehicle configuration and type."]
613 MAV_STANDARD_MODE_LAND = 7,
614 #[doc = "Takeoff mode (auto). Automatic takeoff mode. The precise takeoff behaviour depends on vehicle configuration and type."]
615 MAV_STANDARD_MODE_TAKEOFF = 8,
616}
617impl MavStandardMode {
618 pub const DEFAULT: Self = Self::MAV_STANDARD_MODE_NON_STANDARD;
619}
620impl Default for MavStandardMode {
621 fn default() -> Self {
622 Self::DEFAULT
623 }
624}
625bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly)."] pub struct MavGeneratorStatusFlag : u64 { # [doc = "Generator is off."] const MAV_GENERATOR_STATUS_FLAG_OFF = 1 ; # [doc = "Generator is ready to start generating power."] const MAV_GENERATOR_STATUS_FLAG_READY = 2 ; # [doc = "Generator is generating power."] const MAV_GENERATOR_STATUS_FLAG_GENERATING = 4 ; # [doc = "Generator is charging the batteries (generating enough power to charge and provide the load)."] const MAV_GENERATOR_STATUS_FLAG_CHARGING = 8 ; # [doc = "Generator is operating at a reduced maximum power."] const MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER = 16 ; # [doc = "Generator is providing the maximum output."] const MAV_GENERATOR_STATUS_FLAG_MAXPOWER = 32 ; # [doc = "Generator is near the maximum operating temperature, cooling is insufficient."] const MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING = 64 ; # [doc = "Generator hit the maximum operating temperature and shutdown."] const MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT = 128 ; # [doc = "Power electronics are near the maximum operating temperature, cooling is insufficient."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING = 256 ; # [doc = "Power electronics hit the maximum operating temperature and shutdown."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT = 512 ; # [doc = "Power electronics experienced a fault and shutdown."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT = 1024 ; # [doc = "The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening."] const MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT = 2048 ; # [doc = "Generator controller having communication problems."] const MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING = 4096 ; # [doc = "Power electronic or generator cooling system error."] const MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING = 8192 ; # [doc = "Generator controller power rail experienced a fault."] const MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT = 16384 ; # [doc = "Generator controller exceeded the overcurrent threshold and shutdown to prevent damage."] const MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT = 32768 ; # [doc = "Generator controller detected a high current going into the batteries and shutdown to prevent battery damage."] const MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT = 65536 ; # [doc = "Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating."] const MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT = 131072 ; # [doc = "Batteries are under voltage (generator will not start)."] const MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT = 262144 ; # [doc = "Generator start is inhibited by e.g. a safety switch."] const MAV_GENERATOR_STATUS_FLAG_START_INHIBITED = 524288 ; # [doc = "Generator requires maintenance."] const MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED = 1048576 ; # [doc = "Generator is not ready to generate yet."] const MAV_GENERATOR_STATUS_FLAG_WARMING_UP = 2097152 ; # [doc = "Generator is idle."] const MAV_GENERATOR_STATUS_FLAG_IDLE = 4194304 ; } }
626impl MavGeneratorStatusFlag {
627 pub const DEFAULT: Self = Self::MAV_GENERATOR_STATUS_FLAG_OFF;
628}
629impl Default for MavGeneratorStatusFlag {
630 fn default() -> Self {
631 Self::DEFAULT
632 }
633}
634#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
635#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
636#[cfg_attr(feature = "serde", serde(tag = "type"))]
637#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
638#[repr(u32)]
639#[doc = "Result of mission operation (in a MISSION_ACK message)."]
640pub enum MavMissionResult {
641 #[doc = "mission accepted OK"]
642 MAV_MISSION_ACCEPTED = 0,
643 #[doc = "Generic error / not accepting mission commands at all right now."]
644 MAV_MISSION_ERROR = 1,
645 #[doc = "Coordinate frame is not supported."]
646 MAV_MISSION_UNSUPPORTED_FRAME = 2,
647 #[doc = "Command is not supported."]
648 MAV_MISSION_UNSUPPORTED = 3,
649 #[doc = "Mission items exceed storage space."]
650 MAV_MISSION_NO_SPACE = 4,
651 #[doc = "One of the parameters has an invalid value."]
652 MAV_MISSION_INVALID = 5,
653 #[doc = "param1 has an invalid value."]
654 MAV_MISSION_INVALID_PARAM1 = 6,
655 #[doc = "param2 has an invalid value."]
656 MAV_MISSION_INVALID_PARAM2 = 7,
657 #[doc = "param3 has an invalid value."]
658 MAV_MISSION_INVALID_PARAM3 = 8,
659 #[doc = "param4 has an invalid value."]
660 MAV_MISSION_INVALID_PARAM4 = 9,
661 #[doc = "x / param5 has an invalid value."]
662 MAV_MISSION_INVALID_PARAM5_X = 10,
663 #[doc = "y / param6 has an invalid value."]
664 MAV_MISSION_INVALID_PARAM6_Y = 11,
665 #[doc = "z / param7 has an invalid value."]
666 MAV_MISSION_INVALID_PARAM7 = 12,
667 #[doc = "Mission item received out of sequence"]
668 MAV_MISSION_INVALID_SEQUENCE = 13,
669 #[doc = "Not accepting any mission commands from this communication partner."]
670 MAV_MISSION_DENIED = 14,
671 #[doc = "Current mission operation cancelled (e.g. mission upload, mission download)."]
672 MAV_MISSION_OPERATION_CANCELLED = 15,
673}
674impl MavMissionResult {
675 pub const DEFAULT: Self = Self::MAV_MISSION_ACCEPTED;
676}
677impl Default for MavMissionResult {
678 fn default() -> Self {
679 Self::DEFAULT
680 }
681}
682#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
683#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
684#[cfg_attr(feature = "serde", serde(tag = "type"))]
685#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
686#[repr(u32)]
687#[doc = "Actions for reading/writing parameters between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly parameters are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)"]
688pub enum PreflightStorageParameterAction {
689 #[doc = "Read all parameters from persistent storage. Replaces values in volatile storage."]
690 PARAM_READ_PERSISTENT = 0,
691 #[doc = "Write all parameter values to persistent storage (flash/EEPROM)"]
692 PARAM_WRITE_PERSISTENT = 1,
693 #[doc = "Reset all user configurable parameters to their default value (including airframe selection, sensor calibration data, safety settings, and so on). Does not reset values that contain operation counters and vehicle computed statistics."]
694 PARAM_RESET_CONFIG_DEFAULT = 2,
695 #[doc = "Reset only sensor calibration parameters to factory defaults (or firmware default if not available)"]
696 PARAM_RESET_SENSOR_DEFAULT = 3,
697 #[doc = "Reset all parameters, including operation counters, to default values"]
698 PARAM_RESET_ALL_DEFAULT = 4,
699}
700impl PreflightStorageParameterAction {
701 pub const DEFAULT: Self = Self::PARAM_READ_PERSISTENT;
702}
703impl Default for PreflightStorageParameterAction {
704 fn default() -> Self {
705 Self::DEFAULT
706 }
707}
708#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
709#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
710#[cfg_attr(feature = "serde", serde(tag = "type"))]
711#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
712#[repr(u32)]
713#[doc = "Possible responses from a WIFI_CONFIG_AP message."]
714pub enum WifiConfigApResponse {
715 #[doc = "Undefined response. Likely an indicative of a system that doesn't support this request."]
716 WIFI_CONFIG_AP_RESPONSE_UNDEFINED = 0,
717 #[doc = "Changes accepted."]
718 WIFI_CONFIG_AP_RESPONSE_ACCEPTED = 1,
719 #[doc = "Changes rejected."]
720 WIFI_CONFIG_AP_RESPONSE_REJECTED = 2,
721 #[doc = "Invalid Mode."]
722 WIFI_CONFIG_AP_RESPONSE_MODE_ERROR = 3,
723 #[doc = "Invalid SSID."]
724 WIFI_CONFIG_AP_RESPONSE_SSID_ERROR = 4,
725 #[doc = "Invalid Password."]
726 WIFI_CONFIG_AP_RESPONSE_PASSWORD_ERROR = 5,
727}
728impl WifiConfigApResponse {
729 pub const DEFAULT: Self = Self::WIFI_CONFIG_AP_RESPONSE_UNDEFINED;
730}
731impl Default for WifiConfigApResponse {
732 fn default() -> Self {
733 Self::DEFAULT
734 }
735}
736#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
737#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
738#[cfg_attr(feature = "serde", serde(tag = "type"))]
739#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
740#[repr(u32)]
741#[doc = "Type of AIS vessel, enum duplicated from AIS standard, <https://gpsd.gitlab.io/gpsd/AIVDM.html>"]
742pub enum AisType {
743 #[doc = "Not available (default)."]
744 AIS_TYPE_UNKNOWN = 0,
745 AIS_TYPE_RESERVED_1 = 1,
746 AIS_TYPE_RESERVED_2 = 2,
747 AIS_TYPE_RESERVED_3 = 3,
748 AIS_TYPE_RESERVED_4 = 4,
749 AIS_TYPE_RESERVED_5 = 5,
750 AIS_TYPE_RESERVED_6 = 6,
751 AIS_TYPE_RESERVED_7 = 7,
752 AIS_TYPE_RESERVED_8 = 8,
753 AIS_TYPE_RESERVED_9 = 9,
754 AIS_TYPE_RESERVED_10 = 10,
755 AIS_TYPE_RESERVED_11 = 11,
756 AIS_TYPE_RESERVED_12 = 12,
757 AIS_TYPE_RESERVED_13 = 13,
758 AIS_TYPE_RESERVED_14 = 14,
759 AIS_TYPE_RESERVED_15 = 15,
760 AIS_TYPE_RESERVED_16 = 16,
761 AIS_TYPE_RESERVED_17 = 17,
762 AIS_TYPE_RESERVED_18 = 18,
763 AIS_TYPE_RESERVED_19 = 19,
764 #[doc = "Wing In Ground effect."]
765 AIS_TYPE_WIG = 20,
766 AIS_TYPE_WIG_HAZARDOUS_A = 21,
767 AIS_TYPE_WIG_HAZARDOUS_B = 22,
768 AIS_TYPE_WIG_HAZARDOUS_C = 23,
769 AIS_TYPE_WIG_HAZARDOUS_D = 24,
770 AIS_TYPE_WIG_RESERVED_1 = 25,
771 AIS_TYPE_WIG_RESERVED_2 = 26,
772 AIS_TYPE_WIG_RESERVED_3 = 27,
773 AIS_TYPE_WIG_RESERVED_4 = 28,
774 AIS_TYPE_WIG_RESERVED_5 = 29,
775 AIS_TYPE_FISHING = 30,
776 AIS_TYPE_TOWING = 31,
777 #[doc = "Towing: length exceeds 200m or breadth exceeds 25m."]
778 AIS_TYPE_TOWING_LARGE = 32,
779 #[doc = "Dredging or other underwater ops."]
780 AIS_TYPE_DREDGING = 33,
781 AIS_TYPE_DIVING = 34,
782 AIS_TYPE_MILITARY = 35,
783 AIS_TYPE_SAILING = 36,
784 AIS_TYPE_PLEASURE = 37,
785 AIS_TYPE_RESERVED_20 = 38,
786 AIS_TYPE_RESERVED_21 = 39,
787 #[doc = "High Speed Craft."]
788 AIS_TYPE_HSC = 40,
789 AIS_TYPE_HSC_HAZARDOUS_A = 41,
790 AIS_TYPE_HSC_HAZARDOUS_B = 42,
791 AIS_TYPE_HSC_HAZARDOUS_C = 43,
792 AIS_TYPE_HSC_HAZARDOUS_D = 44,
793 AIS_TYPE_HSC_RESERVED_1 = 45,
794 AIS_TYPE_HSC_RESERVED_2 = 46,
795 AIS_TYPE_HSC_RESERVED_3 = 47,
796 AIS_TYPE_HSC_RESERVED_4 = 48,
797 AIS_TYPE_HSC_UNKNOWN = 49,
798 AIS_TYPE_PILOT = 50,
799 #[doc = "Search And Rescue vessel."]
800 AIS_TYPE_SAR = 51,
801 AIS_TYPE_TUG = 52,
802 AIS_TYPE_PORT_TENDER = 53,
803 #[doc = "Anti-pollution equipment."]
804 AIS_TYPE_ANTI_POLLUTION = 54,
805 AIS_TYPE_LAW_ENFORCEMENT = 55,
806 AIS_TYPE_SPARE_LOCAL_1 = 56,
807 AIS_TYPE_SPARE_LOCAL_2 = 57,
808 AIS_TYPE_MEDICAL_TRANSPORT = 58,
809 #[doc = "Noncombatant ship according to RR Resolution No. 18."]
810 AIS_TYPE_NONECOMBATANT = 59,
811 AIS_TYPE_PASSENGER = 60,
812 AIS_TYPE_PASSENGER_HAZARDOUS_A = 61,
813 AIS_TYPE_PASSENGER_HAZARDOUS_B = 62,
814 AIS_TYPE_PASSENGER_HAZARDOUS_C = 63,
815 AIS_TYPE_PASSENGER_HAZARDOUS_D = 64,
816 AIS_TYPE_PASSENGER_RESERVED_1 = 65,
817 AIS_TYPE_PASSENGER_RESERVED_2 = 66,
818 AIS_TYPE_PASSENGER_RESERVED_3 = 67,
819 AIS_TYPE_PASSENGER_RESERVED_4 = 68,
820 AIS_TYPE_PASSENGER_UNKNOWN = 69,
821 AIS_TYPE_CARGO = 70,
822 AIS_TYPE_CARGO_HAZARDOUS_A = 71,
823 AIS_TYPE_CARGO_HAZARDOUS_B = 72,
824 AIS_TYPE_CARGO_HAZARDOUS_C = 73,
825 AIS_TYPE_CARGO_HAZARDOUS_D = 74,
826 AIS_TYPE_CARGO_RESERVED_1 = 75,
827 AIS_TYPE_CARGO_RESERVED_2 = 76,
828 AIS_TYPE_CARGO_RESERVED_3 = 77,
829 AIS_TYPE_CARGO_RESERVED_4 = 78,
830 AIS_TYPE_CARGO_UNKNOWN = 79,
831 AIS_TYPE_TANKER = 80,
832 AIS_TYPE_TANKER_HAZARDOUS_A = 81,
833 AIS_TYPE_TANKER_HAZARDOUS_B = 82,
834 AIS_TYPE_TANKER_HAZARDOUS_C = 83,
835 AIS_TYPE_TANKER_HAZARDOUS_D = 84,
836 AIS_TYPE_TANKER_RESERVED_1 = 85,
837 AIS_TYPE_TANKER_RESERVED_2 = 86,
838 AIS_TYPE_TANKER_RESERVED_3 = 87,
839 AIS_TYPE_TANKER_RESERVED_4 = 88,
840 AIS_TYPE_TANKER_UNKNOWN = 89,
841 AIS_TYPE_OTHER = 90,
842 AIS_TYPE_OTHER_HAZARDOUS_A = 91,
843 AIS_TYPE_OTHER_HAZARDOUS_B = 92,
844 AIS_TYPE_OTHER_HAZARDOUS_C = 93,
845 AIS_TYPE_OTHER_HAZARDOUS_D = 94,
846 AIS_TYPE_OTHER_RESERVED_1 = 95,
847 AIS_TYPE_OTHER_RESERVED_2 = 96,
848 AIS_TYPE_OTHER_RESERVED_3 = 97,
849 AIS_TYPE_OTHER_RESERVED_4 = 98,
850 AIS_TYPE_OTHER_UNKNOWN = 99,
851}
852impl AisType {
853 pub const DEFAULT: Self = Self::AIS_TYPE_UNKNOWN;
854}
855impl Default for AisType {
856 fn default() -> Self {
857 Self::DEFAULT
858 }
859}
860#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
861#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
862#[cfg_attr(feature = "serde", serde(tag = "type"))]
863#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
864#[repr(u32)]
865#[doc = "Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages."]
866pub enum MavMountMode {
867 #[doc = "Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization"]
868 MAV_MOUNT_MODE_RETRACT = 0,
869 #[doc = "Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory."]
870 MAV_MOUNT_MODE_NEUTRAL = 1,
871 #[doc = "Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization"]
872 MAV_MOUNT_MODE_MAVLINK_TARGETING = 2,
873 #[doc = "Load neutral position and start RC Roll,Pitch,Yaw control with stabilization"]
874 MAV_MOUNT_MODE_RC_TARGETING = 3,
875 #[doc = "Load neutral position and start to point to Lat,Lon,Alt"]
876 MAV_MOUNT_MODE_GPS_POINT = 4,
877 #[doc = "Gimbal tracks system with specified system ID"]
878 MAV_MOUNT_MODE_SYSID_TARGET = 5,
879 #[doc = "Gimbal tracks home position"]
880 MAV_MOUNT_MODE_HOME_LOCATION = 6,
881}
882impl MavMountMode {
883 pub const DEFAULT: Self = Self::MAV_MOUNT_MODE_RETRACT;
884}
885impl Default for MavMountMode {
886 fn default() -> Self {
887 Self::DEFAULT
888 }
889}
890#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
891#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
892#[cfg_attr(feature = "serde", serde(tag = "type"))]
893#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
894#[repr(u32)]
895#[doc = "Actions being taken to mitigate/prevent fence breach"]
896pub enum FenceMitigate {
897 #[doc = "Unknown"]
898 FENCE_MITIGATE_UNKNOWN = 0,
899 #[doc = "No actions being taken"]
900 FENCE_MITIGATE_NONE = 1,
901 #[doc = "Velocity limiting active to prevent breach"]
902 FENCE_MITIGATE_VEL_LIMIT = 2,
903}
904impl FenceMitigate {
905 pub const DEFAULT: Self = Self::FENCE_MITIGATE_UNKNOWN;
906}
907impl Default for FenceMitigate {
908 fn default() -> Self {
909 Self::DEFAULT
910 }
911}
912bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] pub struct GpsInputIgnoreFlags : u16 { # [doc = "ignore altitude field"] const GPS_INPUT_IGNORE_FLAG_ALT = 1 ; # [doc = "ignore hdop field"] const GPS_INPUT_IGNORE_FLAG_HDOP = 2 ; # [doc = "ignore vdop field"] const GPS_INPUT_IGNORE_FLAG_VDOP = 4 ; # [doc = "ignore horizontal velocity field (vn and ve)"] const GPS_INPUT_IGNORE_FLAG_VEL_HORIZ = 8 ; # [doc = "ignore vertical velocity field (vd)"] const GPS_INPUT_IGNORE_FLAG_VEL_VERT = 16 ; # [doc = "ignore speed accuracy field"] const GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY = 32 ; # [doc = "ignore horizontal accuracy field"] const GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY = 64 ; # [doc = "ignore vertical accuracy field"] const GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY = 128 ; } }
913impl GpsInputIgnoreFlags {
914 pub const DEFAULT: Self = Self::GPS_INPUT_IGNORE_FLAG_ALT;
915}
916impl Default for GpsInputIgnoreFlags {
917 fn default() -> Self {
918 Self::DEFAULT
919 }
920}
921#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
922#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
923#[cfg_attr(feature = "serde", serde(tag = "type"))]
924#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
925#[repr(u32)]
926#[doc = "Bitmap of options for the MAV_CMD_DO_REPOSITION"]
927pub enum MavDoRepositionFlags {
928 #[doc = "The aircraft should immediately transition into guided. This should not be set for follow me applications"]
929 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE = 1,
930}
931impl MavDoRepositionFlags {
932 pub const DEFAULT: Self = Self::MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
933}
934impl Default for MavDoRepositionFlags {
935 fn default() -> Self {
936 Self::DEFAULT
937 }
938}
939#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
940#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
941#[cfg_attr(feature = "serde", serde(tag = "type"))]
942#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
943#[repr(u32)]
944#[doc = "Video stream encodings"]
945pub enum VideoStreamEncoding {
946 #[doc = "Stream encoding is unknown"]
947 VIDEO_STREAM_ENCODING_UNKNOWN = 0,
948 #[doc = "Stream encoding is H.264"]
949 VIDEO_STREAM_ENCODING_H264 = 1,
950 #[doc = "Stream encoding is H.265"]
951 VIDEO_STREAM_ENCODING_H265 = 2,
952}
953impl VideoStreamEncoding {
954 pub const DEFAULT: Self = Self::VIDEO_STREAM_ENCODING_UNKNOWN;
955}
956impl Default for VideoStreamEncoding {
957 fn default() -> Self {
958 Self::DEFAULT
959 }
960}
961#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
962#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
963#[cfg_attr(feature = "serde", serde(tag = "type"))]
964#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
965#[repr(u32)]
966#[doc = "These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override."]
967pub enum MavMode {
968 #[doc = "System is not ready to fly, booting, calibrating, etc. No flag is set."]
969 MAV_MODE_PREFLIGHT = 0,
970 #[doc = "System is allowed to be active, under assisted RC control."]
971 MAV_MODE_STABILIZE_DISARMED = 80,
972 #[doc = "System is allowed to be active, under assisted RC control."]
973 MAV_MODE_STABILIZE_ARMED = 208,
974 #[doc = "System is allowed to be active, under manual (RC) control, no stabilization"]
975 MAV_MODE_MANUAL_DISARMED = 64,
976 #[doc = "System is allowed to be active, under manual (RC) control, no stabilization"]
977 MAV_MODE_MANUAL_ARMED = 192,
978 #[doc = "System is allowed to be active, under autonomous control, manual setpoint"]
979 MAV_MODE_GUIDED_DISARMED = 88,
980 #[doc = "System is allowed to be active, under autonomous control, manual setpoint"]
981 MAV_MODE_GUIDED_ARMED = 216,
982 #[doc = "System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)"]
983 MAV_MODE_AUTO_DISARMED = 92,
984 #[doc = "System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)"]
985 MAV_MODE_AUTO_ARMED = 220,
986 #[doc = "UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only."]
987 MAV_MODE_TEST_DISARMED = 66,
988 #[doc = "UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only."]
989 MAV_MODE_TEST_ARMED = 194,
990}
991impl MavMode {
992 pub const DEFAULT: Self = Self::MAV_MODE_PREFLIGHT;
993}
994impl Default for MavMode {
995 fn default() -> Self {
996 Self::DEFAULT
997 }
998}
999#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1000#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1001#[cfg_attr(feature = "serde", serde(tag = "type"))]
1002#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1003#[repr(u32)]
1004#[doc = "Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded."]
1005pub enum MavComponent {
1006 #[doc = "Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message."]
1007 MAV_COMP_ID_ALL = 0,
1008 #[doc = "System flight controller component (\"autopilot\"). Only one autopilot is expected in a particular system."]
1009 MAV_COMP_ID_AUTOPILOT1 = 1,
1010 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1011 MAV_COMP_ID_USER1 = 25,
1012 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1013 MAV_COMP_ID_USER2 = 26,
1014 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1015 MAV_COMP_ID_USER3 = 27,
1016 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1017 MAV_COMP_ID_USER4 = 28,
1018 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1019 MAV_COMP_ID_USER5 = 29,
1020 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1021 MAV_COMP_ID_USER6 = 30,
1022 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1023 MAV_COMP_ID_USER7 = 31,
1024 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1025 MAV_COMP_ID_USER8 = 32,
1026 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1027 MAV_COMP_ID_USER9 = 33,
1028 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1029 MAV_COMP_ID_USER10 = 34,
1030 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1031 MAV_COMP_ID_USER11 = 35,
1032 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1033 MAV_COMP_ID_USER12 = 36,
1034 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1035 MAV_COMP_ID_USER13 = 37,
1036 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1037 MAV_COMP_ID_USER14 = 38,
1038 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1039 MAV_COMP_ID_USER15 = 39,
1040 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1041 MAV_COMP_ID_USER16 = 40,
1042 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1043 MAV_COMP_ID_USER17 = 41,
1044 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1045 MAV_COMP_ID_USER18 = 42,
1046 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1047 MAV_COMP_ID_USER19 = 43,
1048 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1049 MAV_COMP_ID_USER20 = 44,
1050 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1051 MAV_COMP_ID_USER21 = 45,
1052 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1053 MAV_COMP_ID_USER22 = 46,
1054 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1055 MAV_COMP_ID_USER23 = 47,
1056 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1057 MAV_COMP_ID_USER24 = 48,
1058 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1059 MAV_COMP_ID_USER25 = 49,
1060 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1061 MAV_COMP_ID_USER26 = 50,
1062 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1063 MAV_COMP_ID_USER27 = 51,
1064 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1065 MAV_COMP_ID_USER28 = 52,
1066 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1067 MAV_COMP_ID_USER29 = 53,
1068 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1069 MAV_COMP_ID_USER30 = 54,
1070 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1071 MAV_COMP_ID_USER31 = 55,
1072 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1073 MAV_COMP_ID_USER32 = 56,
1074 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1075 MAV_COMP_ID_USER33 = 57,
1076 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1077 MAV_COMP_ID_USER34 = 58,
1078 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1079 MAV_COMP_ID_USER35 = 59,
1080 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1081 MAV_COMP_ID_USER36 = 60,
1082 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1083 MAV_COMP_ID_USER37 = 61,
1084 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1085 MAV_COMP_ID_USER38 = 62,
1086 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1087 MAV_COMP_ID_USER39 = 63,
1088 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1089 MAV_COMP_ID_USER40 = 64,
1090 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1091 MAV_COMP_ID_USER41 = 65,
1092 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1093 MAV_COMP_ID_USER42 = 66,
1094 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1095 MAV_COMP_ID_USER43 = 67,
1096 #[doc = "Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages)."]
1097 MAV_COMP_ID_TELEMETRY_RADIO = 68,
1098 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1099 MAV_COMP_ID_USER45 = 69,
1100 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1101 MAV_COMP_ID_USER46 = 70,
1102 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1103 MAV_COMP_ID_USER47 = 71,
1104 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1105 MAV_COMP_ID_USER48 = 72,
1106 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1107 MAV_COMP_ID_USER49 = 73,
1108 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1109 MAV_COMP_ID_USER50 = 74,
1110 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1111 MAV_COMP_ID_USER51 = 75,
1112 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1113 MAV_COMP_ID_USER52 = 76,
1114 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1115 MAV_COMP_ID_USER53 = 77,
1116 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1117 MAV_COMP_ID_USER54 = 78,
1118 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1119 MAV_COMP_ID_USER55 = 79,
1120 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1121 MAV_COMP_ID_USER56 = 80,
1122 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1123 MAV_COMP_ID_USER57 = 81,
1124 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1125 MAV_COMP_ID_USER58 = 82,
1126 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1127 MAV_COMP_ID_USER59 = 83,
1128 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1129 MAV_COMP_ID_USER60 = 84,
1130 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1131 MAV_COMP_ID_USER61 = 85,
1132 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1133 MAV_COMP_ID_USER62 = 86,
1134 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1135 MAV_COMP_ID_USER63 = 87,
1136 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1137 MAV_COMP_ID_USER64 = 88,
1138 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1139 MAV_COMP_ID_USER65 = 89,
1140 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1141 MAV_COMP_ID_USER66 = 90,
1142 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1143 MAV_COMP_ID_USER67 = 91,
1144 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1145 MAV_COMP_ID_USER68 = 92,
1146 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1147 MAV_COMP_ID_USER69 = 93,
1148 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1149 MAV_COMP_ID_USER70 = 94,
1150 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1151 MAV_COMP_ID_USER71 = 95,
1152 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1153 MAV_COMP_ID_USER72 = 96,
1154 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1155 MAV_COMP_ID_USER73 = 97,
1156 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1157 MAV_COMP_ID_USER74 = 98,
1158 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1159 MAV_COMP_ID_USER75 = 99,
1160 #[doc = "Camera #1."]
1161 MAV_COMP_ID_CAMERA = 100,
1162 #[doc = "Camera #2."]
1163 MAV_COMP_ID_CAMERA2 = 101,
1164 #[doc = "Camera #3."]
1165 MAV_COMP_ID_CAMERA3 = 102,
1166 #[doc = "Camera #4."]
1167 MAV_COMP_ID_CAMERA4 = 103,
1168 #[doc = "Camera #5."]
1169 MAV_COMP_ID_CAMERA5 = 104,
1170 #[doc = "Camera #6."]
1171 MAV_COMP_ID_CAMERA6 = 105,
1172 #[doc = "Servo #1."]
1173 MAV_COMP_ID_SERVO1 = 140,
1174 #[doc = "Servo #2."]
1175 MAV_COMP_ID_SERVO2 = 141,
1176 #[doc = "Servo #3."]
1177 MAV_COMP_ID_SERVO3 = 142,
1178 #[doc = "Servo #4."]
1179 MAV_COMP_ID_SERVO4 = 143,
1180 #[doc = "Servo #5."]
1181 MAV_COMP_ID_SERVO5 = 144,
1182 #[doc = "Servo #6."]
1183 MAV_COMP_ID_SERVO6 = 145,
1184 #[doc = "Servo #7."]
1185 MAV_COMP_ID_SERVO7 = 146,
1186 #[doc = "Servo #8."]
1187 MAV_COMP_ID_SERVO8 = 147,
1188 #[doc = "Servo #9."]
1189 MAV_COMP_ID_SERVO9 = 148,
1190 #[doc = "Servo #10."]
1191 MAV_COMP_ID_SERVO10 = 149,
1192 #[doc = "Servo #11."]
1193 MAV_COMP_ID_SERVO11 = 150,
1194 #[doc = "Servo #12."]
1195 MAV_COMP_ID_SERVO12 = 151,
1196 #[doc = "Servo #13."]
1197 MAV_COMP_ID_SERVO13 = 152,
1198 #[doc = "Servo #14."]
1199 MAV_COMP_ID_SERVO14 = 153,
1200 #[doc = "Gimbal #1."]
1201 MAV_COMP_ID_GIMBAL = 154,
1202 #[doc = "Logging component."]
1203 MAV_COMP_ID_LOG = 155,
1204 #[doc = "Automatic Dependent Surveillance-Broadcast (ADS-B) component."]
1205 MAV_COMP_ID_ADSB = 156,
1206 #[doc = "On Screen Display (OSD) devices for video links."]
1207 MAV_COMP_ID_OSD = 157,
1208 #[doc = "Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice."]
1209 MAV_COMP_ID_PERIPHERAL = 158,
1210 #[doc = "Gimbal ID for QX1."]
1211 MAV_COMP_ID_QX1_GIMBAL = 159,
1212 #[doc = "FLARM collision alert component."]
1213 MAV_COMP_ID_FLARM = 160,
1214 #[doc = "Parachute component."]
1215 MAV_COMP_ID_PARACHUTE = 161,
1216 #[doc = "Winch component."]
1217 MAV_COMP_ID_WINCH = 169,
1218 #[doc = "Gimbal #2."]
1219 MAV_COMP_ID_GIMBAL2 = 171,
1220 #[doc = "Gimbal #3."]
1221 MAV_COMP_ID_GIMBAL3 = 172,
1222 #[doc = "Gimbal #4"]
1223 MAV_COMP_ID_GIMBAL4 = 173,
1224 #[doc = "Gimbal #5."]
1225 MAV_COMP_ID_GIMBAL5 = 174,
1226 #[doc = "Gimbal #6."]
1227 MAV_COMP_ID_GIMBAL6 = 175,
1228 #[doc = "Battery #1."]
1229 MAV_COMP_ID_BATTERY = 180,
1230 #[doc = "Battery #2."]
1231 MAV_COMP_ID_BATTERY2 = 181,
1232 #[doc = "CAN over MAVLink client."]
1233 MAV_COMP_ID_MAVCAN = 189,
1234 #[doc = "Component that can generate/supply a mission flight plan (e.g. GCS or developer API)."]
1235 MAV_COMP_ID_MISSIONPLANNER = 190,
1236 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
1237 MAV_COMP_ID_ONBOARD_COMPUTER = 191,
1238 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
1239 MAV_COMP_ID_ONBOARD_COMPUTER2 = 192,
1240 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
1241 MAV_COMP_ID_ONBOARD_COMPUTER3 = 193,
1242 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
1243 MAV_COMP_ID_ONBOARD_COMPUTER4 = 194,
1244 #[doc = "Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.)."]
1245 MAV_COMP_ID_PATHPLANNER = 195,
1246 #[doc = "Component that plans a collision free path between two points."]
1247 MAV_COMP_ID_OBSTACLE_AVOIDANCE = 196,
1248 #[doc = "Component that provides position estimates using VIO techniques."]
1249 MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY = 197,
1250 #[doc = "Component that manages pairing of vehicle and GCS."]
1251 MAV_COMP_ID_PAIRING_MANAGER = 198,
1252 #[doc = "Inertial Measurement Unit (IMU) #1."]
1253 MAV_COMP_ID_IMU = 200,
1254 #[doc = "Inertial Measurement Unit (IMU) #2."]
1255 MAV_COMP_ID_IMU_2 = 201,
1256 #[doc = "Inertial Measurement Unit (IMU) #3."]
1257 MAV_COMP_ID_IMU_3 = 202,
1258 #[doc = "GPS #1."]
1259 MAV_COMP_ID_GPS = 220,
1260 #[doc = "GPS #2."]
1261 MAV_COMP_ID_GPS2 = 221,
1262 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
1263 MAV_COMP_ID_ODID_TXRX_1 = 236,
1264 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
1265 MAV_COMP_ID_ODID_TXRX_2 = 237,
1266 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
1267 MAV_COMP_ID_ODID_TXRX_3 = 238,
1268 #[doc = "Component to bridge MAVLink to UDP (i.e. from a UART)."]
1269 MAV_COMP_ID_UDP_BRIDGE = 240,
1270 #[doc = "Component to bridge to UART (i.e. from UDP)."]
1271 MAV_COMP_ID_UART_BRIDGE = 241,
1272 #[doc = "Component handling TUNNEL messages (e.g. vendor specific GUI of a component)."]
1273 MAV_COMP_ID_TUNNEL_NODE = 242,
1274 #[doc = "Illuminator"]
1275 MAV_COMP_ID_ILLUMINATOR = 243,
1276 #[doc = "Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.)."]
1277 MAV_COMP_ID_SYSTEM_CONTROL = 250,
1278}
1279impl MavComponent {
1280 pub const DEFAULT: Self = Self::MAV_COMP_ID_ALL;
1281}
1282impl Default for MavComponent {
1283 fn default() -> Self {
1284 Self::DEFAULT
1285 }
1286}
1287#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1288#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1289#[cfg_attr(feature = "serde", serde(tag = "type"))]
1290#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1291#[repr(u32)]
1292#[doc = "Enumeration of the ADSB altimeter types"]
1293pub enum AdsbAltitudeType {
1294 #[doc = "Altitude reported from a Baro source using QNH reference"]
1295 ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0,
1296 #[doc = "Altitude reported from a GNSS source"]
1297 ADSB_ALTITUDE_TYPE_GEOMETRIC = 1,
1298}
1299impl AdsbAltitudeType {
1300 pub const DEFAULT: Self = Self::ADSB_ALTITUDE_TYPE_PRESSURE_QNH;
1301}
1302impl Default for AdsbAltitudeType {
1303 fn default() -> Self {
1304 Self::DEFAULT
1305 }
1306}
1307#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1308#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1309#[cfg_attr(feature = "serde", serde(tag = "type"))]
1310#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1311#[repr(u32)]
1312#[doc = "Cellular network radio type"]
1313pub enum CellularNetworkRadioType {
1314 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0,
1315 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1,
1316 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2,
1317 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3,
1318 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4,
1319}
1320impl CellularNetworkRadioType {
1321 pub const DEFAULT: Self = Self::CELLULAR_NETWORK_RADIO_TYPE_NONE;
1322}
1323impl Default for CellularNetworkRadioType {
1324 fn default() -> Self {
1325 Self::DEFAULT
1326 }
1327}
1328#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1329#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1330#[cfg_attr(feature = "serde", serde(tag = "type"))]
1331#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1332#[repr(u32)]
1333#[doc = "Aircraft-rated danger from this threat."]
1334pub enum MavCollisionThreatLevel {
1335 #[doc = "Not a threat"]
1336 MAV_COLLISION_THREAT_LEVEL_NONE = 0,
1337 #[doc = "Craft is mildly concerned about this threat"]
1338 MAV_COLLISION_THREAT_LEVEL_LOW = 1,
1339 #[doc = "Craft is panicking, and may take actions to avoid threat"]
1340 MAV_COLLISION_THREAT_LEVEL_HIGH = 2,
1341}
1342impl MavCollisionThreatLevel {
1343 pub const DEFAULT: Self = Self::MAV_COLLISION_THREAT_LEVEL_NONE;
1344}
1345impl Default for MavCollisionThreatLevel {
1346 fn default() -> Self {
1347 Self::DEFAULT
1348 }
1349}
1350#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1351#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1352#[cfg_attr(feature = "serde", serde(tag = "type"))]
1353#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1354#[repr(u32)]
1355#[doc = "Specifies the conditions under which the MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN command should be accepted."]
1356pub enum RebootShutdownConditions {
1357 #[doc = "Reboot/Shutdown only if allowed by safety checks, such as being landed."]
1358 REBOOT_SHUTDOWN_CONDITIONS_SAFETY_INTERLOCKED = 0,
1359 #[doc = "Force reboot/shutdown of the autopilot/component regardless of system state."]
1360 REBOOT_SHUTDOWN_CONDITIONS_FORCE = 20190226,
1361}
1362impl RebootShutdownConditions {
1363 pub const DEFAULT: Self = Self::REBOOT_SHUTDOWN_CONDITIONS_SAFETY_INTERLOCKED;
1364}
1365impl Default for RebootShutdownConditions {
1366 fn default() -> Self {
1367 Self::DEFAULT
1368 }
1369}
1370#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1371#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1372#[cfg_attr(feature = "serde", serde(tag = "type"))]
1373#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1374#[repr(u32)]
1375#[doc = "Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. Global frames use the following naming conventions: - \"GLOBAL\": Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. The following modifiers may be used with \"GLOBAL\": - \"RELATIVE_ALT\": Altitude is relative to the vehicle home position rather than MSL. - \"TERRAIN_ALT\": Altitude is relative to ground level rather than MSL. - \"INT\": Latitude/longitude (in degrees) are scaled by multiplying by 1E7. Local frames use the following naming conventions: - \"LOCAL\": Origin of local frame is fixed relative to earth. Unless otherwise specified this origin is the origin of the vehicle position-estimator (\"EKF\"). - \"BODY\": Origin of local frame travels with the vehicle. NOTE, \"BODY\" does NOT indicate alignment of frame axis with vehicle attitude. - \"OFFSET\": Deprecated synonym for \"BODY\" (origin travels with the vehicle). Not to be used for new frames. Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED)."]
1376pub enum MavFrame {
1377 #[doc = "Global (WGS84) coordinate frame + altitude relative to mean sea level (MSL)."]
1378 MAV_FRAME_GLOBAL = 0,
1379 #[doc = "NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth."]
1380 MAV_FRAME_LOCAL_NED = 1,
1381 #[doc = "NOT a coordinate frame, indicates a mission command."]
1382 MAV_FRAME_MISSION = 2,
1383 #[doc = "Global (WGS84) coordinate frame + altitude relative to the home position."]
1384 MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
1385 #[doc = "ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth."]
1386 MAV_FRAME_LOCAL_ENU = 4,
1387 #[doc = "Global (WGS84) coordinate frame (scaled) + altitude relative to mean sea level (MSL)."]
1388 MAV_FRAME_GLOBAL_INT = 5,
1389 #[doc = "Global (WGS84) coordinate frame (scaled) + altitude relative to the home position."]
1390 MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6,
1391 #[doc = "NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle."]
1392 MAV_FRAME_LOCAL_OFFSET_NED = 7,
1393 #[doc = "Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values."]
1394 MAV_FRAME_BODY_NED = 8,
1395 #[doc = "This is the same as MAV_FRAME_BODY_FRD."]
1396 MAV_FRAME_BODY_OFFSET_NED = 9,
1397 #[doc = "Global (WGS84) coordinate frame with AGL altitude (altitude at ground level)."]
1398 MAV_FRAME_GLOBAL_TERRAIN_ALT = 10,
1399 #[doc = "Global (WGS84) coordinate frame (scaled) with AGL altitude (altitude at ground level)."]
1400 MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11,
1401 #[doc = "FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle."]
1402 MAV_FRAME_BODY_FRD = 12,
1403 #[doc = "MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up)."]
1404 MAV_FRAME_RESERVED_13 = 13,
1405 #[doc = "MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down)."]
1406 MAV_FRAME_RESERVED_14 = 14,
1407 #[doc = "MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up)."]
1408 MAV_FRAME_RESERVED_15 = 15,
1409 #[doc = "MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down)."]
1410 MAV_FRAME_RESERVED_16 = 16,
1411 #[doc = "MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up)."]
1412 MAV_FRAME_RESERVED_17 = 17,
1413 #[doc = "MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down)."]
1414 MAV_FRAME_RESERVED_18 = 18,
1415 #[doc = "MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up)."]
1416 MAV_FRAME_RESERVED_19 = 19,
1417 #[doc = "FRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane."]
1418 MAV_FRAME_LOCAL_FRD = 20,
1419 #[doc = "FLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane."]
1420 MAV_FRAME_LOCAL_FLU = 21,
1421}
1422impl MavFrame {
1423 pub const DEFAULT: Self = Self::MAV_FRAME_GLOBAL;
1424}
1425impl Default for MavFrame {
1426 fn default() -> Self {
1427 Self::DEFAULT
1428 }
1429}
1430bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in the HIL_SENSOR message indicate which fields have updated since the last message"] pub struct HilSensorUpdatedFlags : u32 { # [doc = "The value in the xacc field has been updated"] const HIL_SENSOR_UPDATED_XACC = 1 ; # [doc = "The value in the yacc field has been updated"] const HIL_SENSOR_UPDATED_YACC = 2 ; # [doc = "The value in the zacc field has been updated"] const HIL_SENSOR_UPDATED_ZACC = 4 ; # [doc = "The value in the xgyro field has been updated"] const HIL_SENSOR_UPDATED_XGYRO = 8 ; # [doc = "The value in the ygyro field has been updated"] const HIL_SENSOR_UPDATED_YGYRO = 16 ; # [doc = "The value in the zgyro field has been updated"] const HIL_SENSOR_UPDATED_ZGYRO = 32 ; # [doc = "The value in the xmag field has been updated"] const HIL_SENSOR_UPDATED_XMAG = 64 ; # [doc = "The value in the ymag field has been updated"] const HIL_SENSOR_UPDATED_YMAG = 128 ; # [doc = "The value in the zmag field has been updated"] const HIL_SENSOR_UPDATED_ZMAG = 256 ; # [doc = "The value in the abs_pressure field has been updated"] const HIL_SENSOR_UPDATED_ABS_PRESSURE = 512 ; # [doc = "The value in the diff_pressure field has been updated"] const HIL_SENSOR_UPDATED_DIFF_PRESSURE = 1024 ; # [doc = "The value in the pressure_alt field has been updated"] const HIL_SENSOR_UPDATED_PRESSURE_ALT = 2048 ; # [doc = "The value in the temperature field has been updated"] const HIL_SENSOR_UPDATED_TEMPERATURE = 4096 ; # [doc = "Full reset of attitude/position/velocities/etc was performed in sim (Bit 31)."] const HIL_SENSOR_UPDATED_RESET = 2147483648 ; } }
1431impl HilSensorUpdatedFlags {
1432 pub const DEFAULT: Self = Self::HIL_SENSOR_UPDATED_XACC;
1433}
1434impl Default for HilSensorUpdatedFlags {
1435 fn default() -> Self {
1436 Self::DEFAULT
1437 }
1438}
1439#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1440#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1441#[cfg_attr(feature = "serde", serde(tag = "type"))]
1442#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1443#[repr(u32)]
1444#[doc = "MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA)."]
1445pub enum MavType {
1446 #[doc = "Generic micro air vehicle"]
1447 MAV_TYPE_GENERIC = 0,
1448 #[doc = "Fixed wing aircraft."]
1449 MAV_TYPE_FIXED_WING = 1,
1450 #[doc = "Quadrotor"]
1451 MAV_TYPE_QUADROTOR = 2,
1452 #[doc = "Coaxial helicopter"]
1453 MAV_TYPE_COAXIAL = 3,
1454 #[doc = "Normal helicopter with tail rotor."]
1455 MAV_TYPE_HELICOPTER = 4,
1456 #[doc = "Ground installation"]
1457 MAV_TYPE_ANTENNA_TRACKER = 5,
1458 #[doc = "Operator control unit / ground control station"]
1459 MAV_TYPE_GCS = 6,
1460 #[doc = "Airship, controlled"]
1461 MAV_TYPE_AIRSHIP = 7,
1462 #[doc = "Free balloon, uncontrolled"]
1463 MAV_TYPE_FREE_BALLOON = 8,
1464 #[doc = "Rocket"]
1465 MAV_TYPE_ROCKET = 9,
1466 #[doc = "Ground rover"]
1467 MAV_TYPE_GROUND_ROVER = 10,
1468 #[doc = "Surface vessel, boat, ship"]
1469 MAV_TYPE_SURFACE_BOAT = 11,
1470 #[doc = "Submarine"]
1471 MAV_TYPE_SUBMARINE = 12,
1472 #[doc = "Hexarotor"]
1473 MAV_TYPE_HEXAROTOR = 13,
1474 #[doc = "Octorotor"]
1475 MAV_TYPE_OCTOROTOR = 14,
1476 #[doc = "Tricopter"]
1477 MAV_TYPE_TRICOPTER = 15,
1478 #[doc = "Flapping wing"]
1479 MAV_TYPE_FLAPPING_WING = 16,
1480 #[doc = "Kite"]
1481 MAV_TYPE_KITE = 17,
1482 #[doc = "Onboard companion controller"]
1483 MAV_TYPE_ONBOARD_CONTROLLER = 18,
1484 #[doc = "Two-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR."]
1485 MAV_TYPE_VTOL_TAILSITTER_DUOROTOR = 19,
1486 #[doc = "Quad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR."]
1487 MAV_TYPE_VTOL_TAILSITTER_QUADROTOR = 20,
1488 #[doc = "Tiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight."]
1489 MAV_TYPE_VTOL_TILTROTOR = 21,
1490 #[doc = "VTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases."]
1491 MAV_TYPE_VTOL_FIXEDROTOR = 22,
1492 #[doc = "Tailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_TAILSITTER_DUOROTOR or MAV_TYPE_VTOL_TAILSITTER_QUADROTOR if appropriate."]
1493 MAV_TYPE_VTOL_TAILSITTER = 23,
1494 #[doc = "Tiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode."]
1495 MAV_TYPE_VTOL_TILTWING = 24,
1496 #[doc = "VTOL reserved 5"]
1497 MAV_TYPE_VTOL_RESERVED5 = 25,
1498 #[doc = "Gimbal"]
1499 MAV_TYPE_GIMBAL = 26,
1500 #[doc = "ADSB system"]
1501 MAV_TYPE_ADSB = 27,
1502 #[doc = "Steerable, nonrigid airfoil"]
1503 MAV_TYPE_PARAFOIL = 28,
1504 #[doc = "Dodecarotor"]
1505 MAV_TYPE_DODECAROTOR = 29,
1506 #[doc = "Camera"]
1507 MAV_TYPE_CAMERA = 30,
1508 #[doc = "Charging station"]
1509 MAV_TYPE_CHARGING_STATION = 31,
1510 #[doc = "FLARM collision avoidance system"]
1511 MAV_TYPE_FLARM = 32,
1512 #[doc = "Servo"]
1513 MAV_TYPE_SERVO = 33,
1514 #[doc = "Open Drone ID. See <https://mavlink.io/en/services/opendroneid.html>."]
1515 MAV_TYPE_ODID = 34,
1516 #[doc = "Decarotor"]
1517 MAV_TYPE_DECAROTOR = 35,
1518 #[doc = "Battery"]
1519 MAV_TYPE_BATTERY = 36,
1520 #[doc = "Parachute"]
1521 MAV_TYPE_PARACHUTE = 37,
1522 #[doc = "Log"]
1523 MAV_TYPE_LOG = 38,
1524 #[doc = "OSD"]
1525 MAV_TYPE_OSD = 39,
1526 #[doc = "IMU"]
1527 MAV_TYPE_IMU = 40,
1528 #[doc = "GPS"]
1529 MAV_TYPE_GPS = 41,
1530 #[doc = "Winch"]
1531 MAV_TYPE_WINCH = 42,
1532 #[doc = "Generic multirotor that does not fit into a specific type or whose type is unknown"]
1533 MAV_TYPE_GENERIC_MULTIROTOR = 43,
1534 #[doc = "Illuminator. An illuminator is a light source that is used for lighting up dark areas external to the sytstem: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
1535 MAV_TYPE_ILLUMINATOR = 44,
1536 #[doc = "Orbiter spacecraft. Includes satellites orbiting terrestrial and extra-terrestrial bodies. Follows NASA Spacecraft Classification."]
1537 MAV_TYPE_SPACECRAFT_ORBITER = 45,
1538}
1539impl MavType {
1540 pub const DEFAULT: Self = Self::MAV_TYPE_GENERIC;
1541}
1542impl Default for MavType {
1543 fn default() -> Self {
1544 Self::DEFAULT
1545 }
1546}
1547#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1548#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1549#[cfg_attr(feature = "serde", serde(tag = "type"))]
1550#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1551#[repr(u32)]
1552#[doc = "Camera tracking modes"]
1553pub enum CameraTrackingMode {
1554 #[doc = "Not tracking"]
1555 CAMERA_TRACKING_MODE_NONE = 0,
1556 #[doc = "Target is a point"]
1557 CAMERA_TRACKING_MODE_POINT = 1,
1558 #[doc = "Target is a rectangle"]
1559 CAMERA_TRACKING_MODE_RECTANGLE = 2,
1560}
1561impl CameraTrackingMode {
1562 pub const DEFAULT: Self = Self::CAMERA_TRACKING_MODE_NONE;
1563}
1564impl Default for CameraTrackingMode {
1565 fn default() -> Self {
1566 Self::DEFAULT
1567 }
1568}
1569bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Stream status flags (Bitmap)"] pub struct VideoStreamStatusFlags : u16 { # [doc = "Stream is active (running)"] const VIDEO_STREAM_STATUS_FLAGS_RUNNING = 1 ; # [doc = "Stream is thermal imaging"] const VIDEO_STREAM_STATUS_FLAGS_THERMAL = 2 ; # [doc = "Stream can report absolute thermal range (see CAMERA_THERMAL_RANGE)."] const VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED = 4 ; } }
1570impl VideoStreamStatusFlags {
1571 pub const DEFAULT: Self = Self::VIDEO_STREAM_STATUS_FLAGS_RUNNING;
1572}
1573impl Default for VideoStreamStatusFlags {
1574 fn default() -> Self {
1575 Self::DEFAULT
1576 }
1577}
1578#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1579#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1580#[cfg_attr(feature = "serde", serde(tag = "type"))]
1581#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1582#[repr(u32)]
1583#[doc = "Speed setpoint types used in MAV_CMD_DO_CHANGE_SPEED"]
1584pub enum SpeedType {
1585 #[doc = "Airspeed"]
1586 SPEED_TYPE_AIRSPEED = 0,
1587 #[doc = "Groundspeed"]
1588 SPEED_TYPE_GROUNDSPEED = 1,
1589 #[doc = "Climb speed"]
1590 SPEED_TYPE_CLIMB_SPEED = 2,
1591 #[doc = "Descent speed"]
1592 SPEED_TYPE_DESCENT_SPEED = 3,
1593}
1594impl SpeedType {
1595 pub const DEFAULT: Self = Self::SPEED_TYPE_AIRSPEED;
1596}
1597impl Default for SpeedType {
1598 fn default() -> Self {
1599 Self::DEFAULT
1600 }
1601}
1602bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for ADS-B transponder fault report"] pub struct UavionixAdsbOutStatusFault : u8 { const UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL = 8 ; const UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_NO_POS = 16 ; const UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_UNAVAIL = 32 ; const UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL = 64 ; const UAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ = 128 ; } }
1603impl UavionixAdsbOutStatusFault {
1604 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL;
1605}
1606impl Default for UavionixAdsbOutStatusFault {
1607 fn default() -> Self {
1608 Self::DEFAULT
1609 }
1610}
1611#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1612#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1613#[cfg_attr(feature = "serde", serde(tag = "type"))]
1614#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1615#[repr(u32)]
1616#[doc = "Type of GPS fix"]
1617pub enum GpsFixType {
1618 #[doc = "No GPS connected"]
1619 GPS_FIX_TYPE_NO_GPS = 0,
1620 #[doc = "No position information, GPS is connected"]
1621 GPS_FIX_TYPE_NO_FIX = 1,
1622 #[doc = "2D position"]
1623 GPS_FIX_TYPE_2D_FIX = 2,
1624 #[doc = "3D position"]
1625 GPS_FIX_TYPE_3D_FIX = 3,
1626 #[doc = "DGPS/SBAS aided 3D position"]
1627 GPS_FIX_TYPE_DGPS = 4,
1628 #[doc = "RTK float, 3D position"]
1629 GPS_FIX_TYPE_RTK_FLOAT = 5,
1630 #[doc = "RTK Fixed, 3D position"]
1631 GPS_FIX_TYPE_RTK_FIXED = 6,
1632 #[doc = "Static fixed, typically used for base stations"]
1633 GPS_FIX_TYPE_STATIC = 7,
1634 #[doc = "PPP, 3D position."]
1635 GPS_FIX_TYPE_PPP = 8,
1636}
1637impl GpsFixType {
1638 pub const DEFAULT: Self = Self::GPS_FIX_TYPE_NO_GPS;
1639}
1640impl Default for GpsFixType {
1641 fn default() -> Self {
1642 Self::DEFAULT
1643 }
1644}
1645bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These encode the sensors whose status is sent as part of the SYS_STATUS message in the extended fields."] pub struct MavSysStatusSensorExtended : u32 { # [doc = "0x01 Recovery system (parachute, balloon, retracts etc)"] const MAV_SYS_STATUS_RECOVERY_SYSTEM = 1 ; } }
1646impl MavSysStatusSensorExtended {
1647 pub const DEFAULT: Self = Self::MAV_SYS_STATUS_RECOVERY_SYSTEM;
1648}
1649impl Default for MavSysStatusSensorExtended {
1650 fn default() -> Self {
1651 Self::DEFAULT
1652 }
1653}
1654#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1655#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1656#[cfg_attr(feature = "serde", serde(tag = "type"))]
1657#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1658#[repr(u32)]
1659pub enum CanFilterOp {
1660 CAN_FILTER_REPLACE = 0,
1661 CAN_FILTER_ADD = 1,
1662 CAN_FILTER_REMOVE = 2,
1663}
1664impl CanFilterOp {
1665 pub const DEFAULT: Self = Self::CAN_FILTER_REPLACE;
1666}
1667impl Default for CanFilterOp {
1668 fn default() -> Self {
1669 Self::DEFAULT
1670 }
1671}
1672#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1673#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1674#[cfg_attr(feature = "serde", serde(tag = "type"))]
1675#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1676#[repr(u32)]
1677#[doc = "Enumeration of VTOL states"]
1678pub enum MavVtolState {
1679 #[doc = "MAV is not configured as VTOL"]
1680 MAV_VTOL_STATE_UNDEFINED = 0,
1681 #[doc = "VTOL is in transition from multicopter to fixed-wing"]
1682 MAV_VTOL_STATE_TRANSITION_TO_FW = 1,
1683 #[doc = "VTOL is in transition from fixed-wing to multicopter"]
1684 MAV_VTOL_STATE_TRANSITION_TO_MC = 2,
1685 #[doc = "VTOL is in multicopter state"]
1686 MAV_VTOL_STATE_MC = 3,
1687 #[doc = "VTOL is in fixed-wing state"]
1688 MAV_VTOL_STATE_FW = 4,
1689}
1690impl MavVtolState {
1691 pub const DEFAULT: Self = Self::MAV_VTOL_STATE_UNDEFINED;
1692}
1693impl Default for MavVtolState {
1694 fn default() -> Self {
1695 Self::DEFAULT
1696 }
1697}
1698#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1699#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1700#[cfg_attr(feature = "serde", serde(tag = "type"))]
1701#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1702#[repr(u32)]
1703#[doc = "Enumeration of battery types"]
1704pub enum MavBatteryType {
1705 #[doc = "Not specified."]
1706 MAV_BATTERY_TYPE_UNKNOWN = 0,
1707 #[doc = "Lithium polymer battery"]
1708 MAV_BATTERY_TYPE_LIPO = 1,
1709 #[doc = "Lithium-iron-phosphate battery"]
1710 MAV_BATTERY_TYPE_LIFE = 2,
1711 #[doc = "Lithium-ION battery"]
1712 MAV_BATTERY_TYPE_LION = 3,
1713 #[doc = "Nickel metal hydride battery"]
1714 MAV_BATTERY_TYPE_NIMH = 4,
1715}
1716impl MavBatteryType {
1717 pub const DEFAULT: Self = Self::MAV_BATTERY_TYPE_UNKNOWN;
1718}
1719impl Default for MavBatteryType {
1720 fn default() -> Self {
1721 Self::DEFAULT
1722 }
1723}
1724#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1725#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1726#[cfg_attr(feature = "serde", serde(tag = "type"))]
1727#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1728#[repr(u32)]
1729#[doc = "MAV FTP opcodes: <https://mavlink.io/en/services/ftp.html>"]
1730pub enum MavFtpOpcode {
1731 #[doc = "None. Ignored, always ACKed"]
1732 MAV_FTP_OPCODE_NONE = 0,
1733 #[doc = "TerminateSession: Terminates open Read session"]
1734 MAV_FTP_OPCODE_TERMINATESESSION = 1,
1735 #[doc = "ResetSessions: Terminates all open read sessions"]
1736 MAV_FTP_OPCODE_RESETSESSION = 2,
1737 #[doc = "ListDirectory. List files and directories in path from offset"]
1738 MAV_FTP_OPCODE_LISTDIRECTORY = 3,
1739 #[doc = "OpenFileRO: Opens file at path for reading, returns session"]
1740 MAV_FTP_OPCODE_OPENFILERO = 4,
1741 #[doc = "ReadFile: Reads size bytes from offset in session"]
1742 MAV_FTP_OPCODE_READFILE = 5,
1743 #[doc = "CreateFile: Creates file at path for writing, returns session"]
1744 MAV_FTP_OPCODE_CREATEFILE = 6,
1745 #[doc = "WriteFile: Writes size bytes to offset in session"]
1746 MAV_FTP_OPCODE_WRITEFILE = 7,
1747 #[doc = "RemoveFile: Remove file at path"]
1748 MAV_FTP_OPCODE_REMOVEFILE = 8,
1749 #[doc = "CreateDirectory: Creates directory at path"]
1750 MAV_FTP_OPCODE_CREATEDIRECTORY = 9,
1751 #[doc = "RemoveDirectory: Removes directory at path. The directory must be empty."]
1752 MAV_FTP_OPCODE_REMOVEDIRECTORY = 10,
1753 #[doc = "OpenFileWO: Opens file at path for writing, returns session"]
1754 MAV_FTP_OPCODE_OPENFILEWO = 11,
1755 #[doc = "TruncateFile: Truncate file at path to offset length"]
1756 MAV_FTP_OPCODE_TRUNCATEFILE = 12,
1757 #[doc = "Rename: Rename path1 to path2"]
1758 MAV_FTP_OPCODE_RENAME = 13,
1759 #[doc = "CalcFileCRC32: Calculate CRC32 for file at path"]
1760 MAV_FTP_OPCODE_CALCFILECRC = 14,
1761 #[doc = "BurstReadFile: Burst download session file"]
1762 MAV_FTP_OPCODE_BURSTREADFILE = 15,
1763 #[doc = "ACK: ACK response"]
1764 MAV_FTP_OPCODE_ACK = 128,
1765 #[doc = "NAK: NAK response"]
1766 MAV_FTP_OPCODE_NAK = 129,
1767}
1768impl MavFtpOpcode {
1769 pub const DEFAULT: Self = Self::MAV_FTP_OPCODE_NONE;
1770}
1771impl Default for MavFtpOpcode {
1772 fn default() -> Self {
1773 Self::DEFAULT
1774 }
1775}
1776#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1777#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1778#[cfg_attr(feature = "serde", serde(tag = "type"))]
1779#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1780#[repr(u32)]
1781#[doc = "A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages."]
1782pub enum MavDataStream {
1783 #[doc = "Enable all data streams"]
1784 MAV_DATA_STREAM_ALL = 0,
1785 #[doc = "Enable IMU_RAW, GPS_RAW, GPS_STATUS packets."]
1786 MAV_DATA_STREAM_RAW_SENSORS = 1,
1787 #[doc = "Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS"]
1788 MAV_DATA_STREAM_EXTENDED_STATUS = 2,
1789 #[doc = "Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW"]
1790 MAV_DATA_STREAM_RC_CHANNELS = 3,
1791 #[doc = "Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT."]
1792 MAV_DATA_STREAM_RAW_CONTROLLER = 4,
1793 #[doc = "Enable LOCAL_POSITION, GLOBAL_POSITION_INT messages."]
1794 MAV_DATA_STREAM_POSITION = 6,
1795 #[doc = "Dependent on the autopilot"]
1796 MAV_DATA_STREAM_EXTRA1 = 10,
1797 #[doc = "Dependent on the autopilot"]
1798 MAV_DATA_STREAM_EXTRA2 = 11,
1799 #[doc = "Dependent on the autopilot"]
1800 MAV_DATA_STREAM_EXTRA3 = 12,
1801}
1802impl MavDataStream {
1803 pub const DEFAULT: Self = Self::MAV_DATA_STREAM_ALL;
1804}
1805impl Default for MavDataStream {
1806 fn default() -> Self {
1807 Self::DEFAULT
1808 }
1809}
1810#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1811#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1812#[cfg_attr(feature = "serde", serde(tag = "type"))]
1813#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1814#[repr(u32)]
1815#[doc = "Flags for CURRENT_EVENT_SEQUENCE."]
1816pub enum MavEventCurrentSequenceFlags {
1817 #[doc = "A sequence reset has happened (e.g. vehicle reboot)."]
1818 MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET = 1,
1819}
1820impl MavEventCurrentSequenceFlags {
1821 pub const DEFAULT: Self = Self::MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET;
1822}
1823impl Default for MavEventCurrentSequenceFlags {
1824 fn default() -> Self {
1825 Self::DEFAULT
1826 }
1827}
1828#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1829#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1830#[cfg_attr(feature = "serde", serde(tag = "type"))]
1831#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1832#[repr(u32)]
1833#[doc = "RC type. Used in MAV_CMD_START_RX_PAIR."]
1834pub enum RcType {
1835 #[doc = "Spektrum"]
1836 RC_TYPE_SPEKTRUM = 0,
1837 #[doc = "CRSF"]
1838 RC_TYPE_CRSF = 1,
1839}
1840impl RcType {
1841 pub const DEFAULT: Self = Self::RC_TYPE_SPEKTRUM;
1842}
1843impl Default for RcType {
1844 fn default() -> Self {
1845 Self::DEFAULT
1846 }
1847}
1848bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal device (low level) error flags (bitmap, 0 means no error)"] pub struct GimbalDeviceErrorFlags : u32 { # [doc = "Gimbal device is limited by hardware roll limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT = 1 ; # [doc = "Gimbal device is limited by hardware pitch limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT = 2 ; # [doc = "Gimbal device is limited by hardware yaw limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT = 4 ; # [doc = "There is an error with the gimbal encoders."] const GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR = 8 ; # [doc = "There is an error with the gimbal power source."] const GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR = 16 ; # [doc = "There is an error with the gimbal motors."] const GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR = 32 ; # [doc = "There is an error with the gimbal's software."] const GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR = 64 ; # [doc = "There is an error with the gimbal's communication."] const GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR = 128 ; # [doc = "Gimbal device is currently calibrating."] const GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING = 256 ; # [doc = "Gimbal device is not assigned to a gimbal manager."] const GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER = 512 ; } }
1849impl GimbalDeviceErrorFlags {
1850 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT;
1851}
1852impl Default for GimbalDeviceErrorFlags {
1853 fn default() -> Self {
1854 Self::DEFAULT
1855 }
1856}
1857#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1858#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1859#[cfg_attr(feature = "serde", serde(tag = "type"))]
1860#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1861#[repr(u32)]
1862pub enum MavOdidOperatorIdType {
1863 #[doc = "CAA (Civil Aviation Authority) registered operator ID."]
1864 MAV_ODID_OPERATOR_ID_TYPE_CAA = 0,
1865}
1866impl MavOdidOperatorIdType {
1867 pub const DEFAULT: Self = Self::MAV_ODID_OPERATOR_ID_TYPE_CAA;
1868}
1869impl Default for MavOdidOperatorIdType {
1870 fn default() -> Self {
1871 Self::DEFAULT
1872 }
1873}
1874#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1875#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1876#[cfg_attr(feature = "serde", serde(tag = "type"))]
1877#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1878#[repr(u32)]
1879#[doc = "Flags to indicate the type of storage."]
1880pub enum StorageType {
1881 #[doc = "Storage type is not known."]
1882 STORAGE_TYPE_UNKNOWN = 0,
1883 #[doc = "Storage type is USB device."]
1884 STORAGE_TYPE_USB_STICK = 1,
1885 #[doc = "Storage type is SD card."]
1886 STORAGE_TYPE_SD = 2,
1887 #[doc = "Storage type is microSD card."]
1888 STORAGE_TYPE_MICROSD = 3,
1889 #[doc = "Storage type is CFast."]
1890 STORAGE_TYPE_CF = 4,
1891 #[doc = "Storage type is CFexpress."]
1892 STORAGE_TYPE_CFE = 5,
1893 #[doc = "Storage type is XQD."]
1894 STORAGE_TYPE_XQD = 6,
1895 #[doc = "Storage type is HD mass storage type."]
1896 STORAGE_TYPE_HD = 7,
1897 #[doc = "Storage type is other, not listed type."]
1898 STORAGE_TYPE_OTHER = 254,
1899}
1900impl StorageType {
1901 pub const DEFAULT: Self = Self::STORAGE_TYPE_UNKNOWN;
1902}
1903impl Default for StorageType {
1904 fn default() -> Self {
1905 Self::DEFAULT
1906 }
1907}
1908bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "SERIAL_CONTROL flags (bitmask)"] pub struct SerialControlFlag : u8 { # [doc = "Set if this is a reply"] const SERIAL_CONTROL_FLAG_REPLY = 1 ; # [doc = "Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message"] const SERIAL_CONTROL_FLAG_RESPOND = 2 ; # [doc = "Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set"] const SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 ; # [doc = "Block on writes to the serial port"] const SERIAL_CONTROL_FLAG_BLOCKING = 8 ; # [doc = "Send multiple replies until port is drained"] const SERIAL_CONTROL_FLAG_MULTI = 16 ; } }
1909impl SerialControlFlag {
1910 pub const DEFAULT: Self = Self::SERIAL_CONTROL_FLAG_REPLY;
1911}
1912impl Default for SerialControlFlag {
1913 fn default() -> Self {
1914 Self::DEFAULT
1915 }
1916}
1917#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1918#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1919#[cfg_attr(feature = "serde", serde(tag = "type"))]
1920#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1921#[repr(u32)]
1922#[doc = "Axes that will be autotuned by MAV_CMD_DO_AUTOTUNE_ENABLE. Note that at least one flag must be set in MAV_CMD_DO_AUTOTUNE_ENABLE.param2: if none are set, the flight stack will tune its default set of axes."]
1923pub enum AutotuneAxis {
1924 #[doc = "Autotune roll axis."]
1925 AUTOTUNE_AXIS_ROLL = 1,
1926 #[doc = "Autotune pitch axis."]
1927 AUTOTUNE_AXIS_PITCH = 2,
1928 #[doc = "Autotune yaw axis."]
1929 AUTOTUNE_AXIS_YAW = 4,
1930}
1931impl AutotuneAxis {
1932 pub const DEFAULT: Self = Self::AUTOTUNE_AXIS_ROLL;
1933}
1934impl Default for AutotuneAxis {
1935 fn default() -> Self {
1936 Self::DEFAULT
1937 }
1938}
1939#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1940#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1941#[cfg_attr(feature = "serde", serde(tag = "type"))]
1942#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1943#[repr(u32)]
1944pub enum MavOdidDescType {
1945 #[doc = "Optional free-form text description of the purpose of the flight."]
1946 MAV_ODID_DESC_TYPE_TEXT = 0,
1947 #[doc = "Optional additional clarification when status == MAV_ODID_STATUS_EMERGENCY."]
1948 MAV_ODID_DESC_TYPE_EMERGENCY = 1,
1949 #[doc = "Optional additional clarification when status != MAV_ODID_STATUS_EMERGENCY."]
1950 MAV_ODID_DESC_TYPE_EXTENDED_STATUS = 2,
1951}
1952impl MavOdidDescType {
1953 pub const DEFAULT: Self = Self::MAV_ODID_DESC_TYPE_TEXT;
1954}
1955impl Default for MavOdidDescType {
1956 fn default() -> Self {
1957 Self::DEFAULT
1958 }
1959}
1960#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1961#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1962#[cfg_attr(feature = "serde", serde(tag = "type"))]
1963#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1964#[repr(u32)]
1965#[doc = "Enumeration of landed detector states"]
1966pub enum MavLandedState {
1967 #[doc = "MAV landed state is unknown"]
1968 MAV_LANDED_STATE_UNDEFINED = 0,
1969 #[doc = "MAV is landed (on ground)"]
1970 MAV_LANDED_STATE_ON_GROUND = 1,
1971 #[doc = "MAV is in air"]
1972 MAV_LANDED_STATE_IN_AIR = 2,
1973 #[doc = "MAV currently taking off"]
1974 MAV_LANDED_STATE_TAKEOFF = 3,
1975 #[doc = "MAV currently landing"]
1976 MAV_LANDED_STATE_LANDING = 4,
1977}
1978impl MavLandedState {
1979 pub const DEFAULT: Self = Self::MAV_LANDED_STATE_UNDEFINED;
1980}
1981impl Default for MavLandedState {
1982 fn default() -> Self {
1983 Self::DEFAULT
1984 }
1985}
1986#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1987#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1988#[cfg_attr(feature = "serde", serde(tag = "type"))]
1989#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1990#[repr(u32)]
1991#[doc = "Sequence that motors are tested when using MAV_CMD_DO_MOTOR_TEST."]
1992pub enum MotorTestOrder {
1993 #[doc = "Default autopilot motor test method."]
1994 MOTOR_TEST_ORDER_DEFAULT = 0,
1995 #[doc = "Motor numbers are specified as their index in a predefined vehicle-specific sequence."]
1996 MOTOR_TEST_ORDER_SEQUENCE = 1,
1997 #[doc = "Motor numbers are specified as the output as labeled on the board."]
1998 MOTOR_TEST_ORDER_BOARD = 2,
1999}
2000impl MotorTestOrder {
2001 pub const DEFAULT: Self = Self::MOTOR_TEST_ORDER_DEFAULT;
2002}
2003impl Default for MotorTestOrder {
2004 fn default() -> Self {
2005 Self::DEFAULT
2006 }
2007}
2008bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Camera capability flags (Bitmap)"] pub struct CameraCapFlags : u32 { # [doc = "Camera is able to record video"] const CAMERA_CAP_FLAGS_CAPTURE_VIDEO = 1 ; # [doc = "Camera is able to capture images"] const CAMERA_CAP_FLAGS_CAPTURE_IMAGE = 2 ; # [doc = "Camera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE)"] const CAMERA_CAP_FLAGS_HAS_MODES = 4 ; # [doc = "Camera can capture images while in video mode"] const CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = 8 ; # [doc = "Camera can capture videos while in Photo/Image mode"] const CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = 16 ; # [doc = "Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE)"] const CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = 32 ; # [doc = "Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM)"] const CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = 64 ; # [doc = "Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS)"] const CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = 128 ; # [doc = "Camera has video streaming capabilities (request VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video streaming info)"] const CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = 256 ; # [doc = "Camera supports tracking of a point on the camera view."] const CAMERA_CAP_FLAGS_HAS_TRACKING_POINT = 512 ; # [doc = "Camera supports tracking of a selection rectangle on the camera view."] const CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = 1024 ; # [doc = "Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS)."] const CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = 2048 ; # [doc = "Camera supports absolute thermal range (request CAMERA_THERMAL_RANGE with MAV_CMD_REQUEST_MESSAGE)."] const CAMERA_CAP_FLAGS_HAS_THERMAL_RANGE = 4096 ; } }
2009impl CameraCapFlags {
2010 pub const DEFAULT: Self = Self::CAMERA_CAP_FLAGS_CAPTURE_VIDEO;
2011}
2012impl Default for CameraCapFlags {
2013 fn default() -> Self {
2014 Self::DEFAULT
2015 }
2016}
2017#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2018#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2019#[cfg_attr(feature = "serde", serde(tag = "type"))]
2020#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2021#[repr(u32)]
2022#[doc = "Modes of illuminator"]
2023pub enum IlluminatorMode {
2024 #[doc = "Illuminator mode is not specified/unknown"]
2025 ILLUMINATOR_MODE_UNKNOWN = 0,
2026 #[doc = "Illuminator behavior is controlled by MAV_CMD_DO_ILLUMINATOR_CONFIGURE settings"]
2027 ILLUMINATOR_MODE_INTERNAL_CONTROL = 1,
2028 #[doc = "Illuminator behavior is controlled by external factors: e.g. an external hardware signal"]
2029 ILLUMINATOR_MODE_EXTERNAL_SYNC = 2,
2030}
2031impl IlluminatorMode {
2032 pub const DEFAULT: Self = Self::ILLUMINATOR_MODE_UNKNOWN;
2033}
2034impl Default for IlluminatorMode {
2035 fn default() -> Self {
2036 Self::DEFAULT
2037 }
2038}
2039#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2040#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2041#[cfg_attr(feature = "serde", serde(tag = "type"))]
2042#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2043#[repr(u32)]
2044#[doc = "Fence types to enable or disable when using MAV_CMD_DO_FENCE_ENABLE. Note that at least one of these flags must be set in MAV_CMD_DO_FENCE_ENABLE.param2. If none are set, the flight stack will ignore the field and enable/disable its default set of fences (usually all of them)."]
2045pub enum FenceType {
2046 #[doc = "Maximum altitude fence"]
2047 FENCE_TYPE_ALT_MAX = 1,
2048 #[doc = "Circle fence"]
2049 FENCE_TYPE_CIRCLE = 2,
2050 #[doc = "Polygon fence"]
2051 FENCE_TYPE_POLYGON = 4,
2052 #[doc = "Minimum altitude fence"]
2053 FENCE_TYPE_ALT_MIN = 8,
2054}
2055impl FenceType {
2056 pub const DEFAULT: Self = Self::FENCE_TYPE_ALT_MAX;
2057}
2058impl Default for FenceType {
2059 fn default() -> Self {
2060 Self::DEFAULT
2061 }
2062}
2063#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2064#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2065#[cfg_attr(feature = "serde", serde(tag = "type"))]
2066#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2067#[repr(u32)]
2068#[doc = "Zoom types for MAV_CMD_SET_CAMERA_ZOOM"]
2069pub enum CameraZoomType {
2070 #[doc = "Zoom one step increment (-1 for wide, 1 for tele)"]
2071 ZOOM_TYPE_STEP = 0,
2072 #[doc = "Continuous normalized zoom in/out rate until stopped. Range -1..1, negative: wide, positive: narrow/tele, 0 to stop zooming. Other values should be clipped to the range."]
2073 ZOOM_TYPE_CONTINUOUS = 1,
2074 #[doc = "Zoom value as proportion of full camera range (a percentage value between 0.0 and 100.0)"]
2075 ZOOM_TYPE_RANGE = 2,
2076 #[doc = "Zoom value/variable focal length in millimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)"]
2077 ZOOM_TYPE_FOCAL_LENGTH = 3,
2078 #[doc = "Zoom value as horizontal field of view in degrees."]
2079 ZOOM_TYPE_HORIZONTAL_FOV = 4,
2080}
2081impl CameraZoomType {
2082 pub const DEFAULT: Self = Self::ZOOM_TYPE_STEP;
2083}
2084impl Default for CameraZoomType {
2085 fn default() -> Self {
2086 Self::DEFAULT
2087 }
2088}
2089#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2090#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2091#[cfg_attr(feature = "serde", serde(tag = "type"))]
2092#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2093#[repr(u32)]
2094pub enum MavOdidClassificationType {
2095 #[doc = "The classification type for the UA is undeclared."]
2096 MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED = 0,
2097 #[doc = "The classification type for the UA follows EU (European Union) specifications."]
2098 MAV_ODID_CLASSIFICATION_TYPE_EU = 1,
2099}
2100impl MavOdidClassificationType {
2101 pub const DEFAULT: Self = Self::MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED;
2102}
2103impl Default for MavOdidClassificationType {
2104 fn default() -> Self {
2105 Self::DEFAULT
2106 }
2107}
2108bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags indicate status such as data validity of each data source. Set = data valid"] pub struct AdsbFlags : u16 { const ADSB_FLAGS_VALID_COORDS = 1 ; const ADSB_FLAGS_VALID_ALTITUDE = 2 ; const ADSB_FLAGS_VALID_HEADING = 4 ; const ADSB_FLAGS_VALID_VELOCITY = 8 ; const ADSB_FLAGS_VALID_CALLSIGN = 16 ; const ADSB_FLAGS_VALID_SQUAWK = 32 ; const ADSB_FLAGS_SIMULATED = 64 ; const ADSB_FLAGS_VERTICAL_VELOCITY_VALID = 128 ; const ADSB_FLAGS_BARO_VALID = 256 ; const ADSB_FLAGS_SOURCE_UAT = 32768 ; } }
2109impl AdsbFlags {
2110 pub const DEFAULT: Self = Self::ADSB_FLAGS_VALID_COORDS;
2111}
2112impl Default for AdsbFlags {
2113 fn default() -> Self {
2114 Self::DEFAULT
2115 }
2116}
2117#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2118#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2119#[cfg_attr(feature = "serde", serde(tag = "type"))]
2120#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2121#[repr(u32)]
2122#[doc = "Direction of VTOL transition"]
2123pub enum VtolTransitionHeading {
2124 #[doc = "Respect the heading configuration of the vehicle."]
2125 VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT = 0,
2126 #[doc = "Use the heading pointing towards the next waypoint."]
2127 VTOL_TRANSITION_HEADING_NEXT_WAYPOINT = 1,
2128 #[doc = "Use the heading on takeoff (while sitting on the ground)."]
2129 VTOL_TRANSITION_HEADING_TAKEOFF = 2,
2130 #[doc = "Use the specified heading in parameter 4."]
2131 VTOL_TRANSITION_HEADING_SPECIFIED = 3,
2132 #[doc = "Use the current heading when reaching takeoff altitude (potentially facing the wind when weather-vaning is active)."]
2133 VTOL_TRANSITION_HEADING_ANY = 4,
2134}
2135impl VtolTransitionHeading {
2136 pub const DEFAULT: Self = Self::VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT;
2137}
2138impl Default for VtolTransitionHeading {
2139 fn default() -> Self {
2140 Self::DEFAULT
2141 }
2142}
2143#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2144#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2145#[cfg_attr(feature = "serde", serde(tag = "type"))]
2146#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2147#[repr(u32)]
2148#[doc = "Type of mission items being requested/sent in mission protocol."]
2149pub enum MavMissionType {
2150 #[doc = "Items are mission commands for main mission."]
2151 MAV_MISSION_TYPE_MISSION = 0,
2152 #[doc = "Specifies GeoFence area(s). Items are MAV_CMD_NAV_FENCE_ GeoFence items."]
2153 MAV_MISSION_TYPE_FENCE = 1,
2154 #[doc = "Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_NAV_RALLY_POINT rally point items."]
2155 MAV_MISSION_TYPE_RALLY = 2,
2156 #[doc = "Only used in MISSION_CLEAR_ALL to clear all mission types."]
2157 MAV_MISSION_TYPE_ALL = 255,
2158}
2159impl MavMissionType {
2160 pub const DEFAULT: Self = Self::MAV_MISSION_TYPE_MISSION;
2161}
2162impl Default for MavMissionType {
2163 fn default() -> Self {
2164 Self::DEFAULT
2165 }
2166}
2167#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2168#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2169#[cfg_attr(feature = "serde", serde(tag = "type"))]
2170#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2171#[repr(u32)]
2172pub enum MavOdidUaType {
2173 #[doc = "No UA (Unmanned Aircraft) type defined."]
2174 MAV_ODID_UA_TYPE_NONE = 0,
2175 #[doc = "Aeroplane/Airplane. Fixed wing."]
2176 MAV_ODID_UA_TYPE_AEROPLANE = 1,
2177 #[doc = "Helicopter or multirotor."]
2178 MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR = 2,
2179 #[doc = "Gyroplane."]
2180 MAV_ODID_UA_TYPE_GYROPLANE = 3,
2181 #[doc = "VTOL (Vertical Take-Off and Landing). Fixed wing aircraft that can take off vertically."]
2182 MAV_ODID_UA_TYPE_HYBRID_LIFT = 4,
2183 #[doc = "Ornithopter."]
2184 MAV_ODID_UA_TYPE_ORNITHOPTER = 5,
2185 #[doc = "Glider."]
2186 MAV_ODID_UA_TYPE_GLIDER = 6,
2187 #[doc = "Kite."]
2188 MAV_ODID_UA_TYPE_KITE = 7,
2189 #[doc = "Free Balloon."]
2190 MAV_ODID_UA_TYPE_FREE_BALLOON = 8,
2191 #[doc = "Captive Balloon."]
2192 MAV_ODID_UA_TYPE_CAPTIVE_BALLOON = 9,
2193 #[doc = "Airship. E.g. a blimp."]
2194 MAV_ODID_UA_TYPE_AIRSHIP = 10,
2195 #[doc = "Free Fall/Parachute (unpowered)."]
2196 MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE = 11,
2197 #[doc = "Rocket."]
2198 MAV_ODID_UA_TYPE_ROCKET = 12,
2199 #[doc = "Tethered powered aircraft."]
2200 MAV_ODID_UA_TYPE_TETHERED_POWERED_AIRCRAFT = 13,
2201 #[doc = "Ground Obstacle."]
2202 MAV_ODID_UA_TYPE_GROUND_OBSTACLE = 14,
2203 #[doc = "Other type of aircraft not listed earlier."]
2204 MAV_ODID_UA_TYPE_OTHER = 15,
2205}
2206impl MavOdidUaType {
2207 pub const DEFAULT: Self = Self::MAV_ODID_UA_TYPE_NONE;
2208}
2209impl Default for MavOdidUaType {
2210 fn default() -> Self {
2211 Self::DEFAULT
2212 }
2213}
2214#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2215#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2216#[cfg_attr(feature = "serde", serde(tag = "type"))]
2217#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2218#[repr(u32)]
2219pub enum MavOdidVerAcc {
2220 #[doc = "The vertical accuracy is unknown."]
2221 MAV_ODID_VER_ACC_UNKNOWN = 0,
2222 #[doc = "The vertical accuracy is smaller than 150 meter."]
2223 MAV_ODID_VER_ACC_150_METER = 1,
2224 #[doc = "The vertical accuracy is smaller than 45 meter."]
2225 MAV_ODID_VER_ACC_45_METER = 2,
2226 #[doc = "The vertical accuracy is smaller than 25 meter."]
2227 MAV_ODID_VER_ACC_25_METER = 3,
2228 #[doc = "The vertical accuracy is smaller than 10 meter."]
2229 MAV_ODID_VER_ACC_10_METER = 4,
2230 #[doc = "The vertical accuracy is smaller than 3 meter."]
2231 MAV_ODID_VER_ACC_3_METER = 5,
2232 #[doc = "The vertical accuracy is smaller than 1 meter."]
2233 MAV_ODID_VER_ACC_1_METER = 6,
2234}
2235impl MavOdidVerAcc {
2236 pub const DEFAULT: Self = Self::MAV_ODID_VER_ACC_UNKNOWN;
2237}
2238impl Default for MavOdidVerAcc {
2239 fn default() -> Self {
2240 Self::DEFAULT
2241 }
2242}
2243#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2244#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2245#[cfg_attr(feature = "serde", serde(tag = "type"))]
2246#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2247#[repr(u32)]
2248#[doc = "These flags are used to diagnose the failure state of CELLULAR_STATUS"]
2249pub enum CellularNetworkFailedReason {
2250 #[doc = "No error"]
2251 CELLULAR_NETWORK_FAILED_REASON_NONE = 0,
2252 #[doc = "Error state is unknown"]
2253 CELLULAR_NETWORK_FAILED_REASON_UNKNOWN = 1,
2254 #[doc = "SIM is required for the modem but missing"]
2255 CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING = 2,
2256 #[doc = "SIM is available, but not usable for connection"]
2257 CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR = 3,
2258}
2259impl CellularNetworkFailedReason {
2260 pub const DEFAULT: Self = Self::CELLULAR_NETWORK_FAILED_REASON_NONE;
2261}
2262impl Default for CellularNetworkFailedReason {
2263 fn default() -> Self {
2264 Self::DEFAULT
2265 }
2266}
2267#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2268#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2269#[cfg_attr(feature = "serde", serde(tag = "type"))]
2270#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2271#[repr(u32)]
2272#[doc = "Specifies the datatype of a MAVLink parameter."]
2273pub enum MavParamType {
2274 #[doc = "8-bit unsigned integer"]
2275 MAV_PARAM_TYPE_UINT8 = 1,
2276 #[doc = "8-bit signed integer"]
2277 MAV_PARAM_TYPE_INT8 = 2,
2278 #[doc = "16-bit unsigned integer"]
2279 MAV_PARAM_TYPE_UINT16 = 3,
2280 #[doc = "16-bit signed integer"]
2281 MAV_PARAM_TYPE_INT16 = 4,
2282 #[doc = "32-bit unsigned integer"]
2283 MAV_PARAM_TYPE_UINT32 = 5,
2284 #[doc = "32-bit signed integer"]
2285 MAV_PARAM_TYPE_INT32 = 6,
2286 #[doc = "64-bit unsigned integer"]
2287 MAV_PARAM_TYPE_UINT64 = 7,
2288 #[doc = "64-bit signed integer"]
2289 MAV_PARAM_TYPE_INT64 = 8,
2290 #[doc = "32-bit floating-point"]
2291 MAV_PARAM_TYPE_REAL32 = 9,
2292 #[doc = "64-bit floating-point"]
2293 MAV_PARAM_TYPE_REAL64 = 10,
2294}
2295impl MavParamType {
2296 pub const DEFAULT: Self = Self::MAV_PARAM_TYPE_UINT8;
2297}
2298impl Default for MavParamType {
2299 fn default() -> Self {
2300 Self::DEFAULT
2301 }
2302}
2303#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2304#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2305#[cfg_attr(feature = "serde", serde(tag = "type"))]
2306#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2307#[repr(u32)]
2308#[doc = "Enumeration of sensor orientation, according to its rotations"]
2309pub enum MavSensorOrientation {
2310 #[doc = "Roll: 0, Pitch: 0, Yaw: 0"]
2311 MAV_SENSOR_ROTATION_NONE = 0,
2312 #[doc = "Roll: 0, Pitch: 0, Yaw: 45"]
2313 MAV_SENSOR_ROTATION_YAW_45 = 1,
2314 #[doc = "Roll: 0, Pitch: 0, Yaw: 90"]
2315 MAV_SENSOR_ROTATION_YAW_90 = 2,
2316 #[doc = "Roll: 0, Pitch: 0, Yaw: 135"]
2317 MAV_SENSOR_ROTATION_YAW_135 = 3,
2318 #[doc = "Roll: 0, Pitch: 0, Yaw: 180"]
2319 MAV_SENSOR_ROTATION_YAW_180 = 4,
2320 #[doc = "Roll: 0, Pitch: 0, Yaw: 225"]
2321 MAV_SENSOR_ROTATION_YAW_225 = 5,
2322 #[doc = "Roll: 0, Pitch: 0, Yaw: 270"]
2323 MAV_SENSOR_ROTATION_YAW_270 = 6,
2324 #[doc = "Roll: 0, Pitch: 0, Yaw: 315"]
2325 MAV_SENSOR_ROTATION_YAW_315 = 7,
2326 #[doc = "Roll: 180, Pitch: 0, Yaw: 0"]
2327 MAV_SENSOR_ROTATION_ROLL_180 = 8,
2328 #[doc = "Roll: 180, Pitch: 0, Yaw: 45"]
2329 MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9,
2330 #[doc = "Roll: 180, Pitch: 0, Yaw: 90"]
2331 MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10,
2332 #[doc = "Roll: 180, Pitch: 0, Yaw: 135"]
2333 MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11,
2334 #[doc = "Roll: 0, Pitch: 180, Yaw: 0"]
2335 MAV_SENSOR_ROTATION_PITCH_180 = 12,
2336 #[doc = "Roll: 180, Pitch: 0, Yaw: 225"]
2337 MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13,
2338 #[doc = "Roll: 180, Pitch: 0, Yaw: 270"]
2339 MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14,
2340 #[doc = "Roll: 180, Pitch: 0, Yaw: 315"]
2341 MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15,
2342 #[doc = "Roll: 90, Pitch: 0, Yaw: 0"]
2343 MAV_SENSOR_ROTATION_ROLL_90 = 16,
2344 #[doc = "Roll: 90, Pitch: 0, Yaw: 45"]
2345 MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17,
2346 #[doc = "Roll: 90, Pitch: 0, Yaw: 90"]
2347 MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18,
2348 #[doc = "Roll: 90, Pitch: 0, Yaw: 135"]
2349 MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19,
2350 #[doc = "Roll: 270, Pitch: 0, Yaw: 0"]
2351 MAV_SENSOR_ROTATION_ROLL_270 = 20,
2352 #[doc = "Roll: 270, Pitch: 0, Yaw: 45"]
2353 MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21,
2354 #[doc = "Roll: 270, Pitch: 0, Yaw: 90"]
2355 MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22,
2356 #[doc = "Roll: 270, Pitch: 0, Yaw: 135"]
2357 MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23,
2358 #[doc = "Roll: 0, Pitch: 90, Yaw: 0"]
2359 MAV_SENSOR_ROTATION_PITCH_90 = 24,
2360 #[doc = "Roll: 0, Pitch: 270, Yaw: 0"]
2361 MAV_SENSOR_ROTATION_PITCH_270 = 25,
2362 #[doc = "Roll: 0, Pitch: 180, Yaw: 90"]
2363 MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26,
2364 #[doc = "Roll: 0, Pitch: 180, Yaw: 270"]
2365 MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27,
2366 #[doc = "Roll: 90, Pitch: 90, Yaw: 0"]
2367 MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28,
2368 #[doc = "Roll: 180, Pitch: 90, Yaw: 0"]
2369 MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29,
2370 #[doc = "Roll: 270, Pitch: 90, Yaw: 0"]
2371 MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30,
2372 #[doc = "Roll: 90, Pitch: 180, Yaw: 0"]
2373 MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31,
2374 #[doc = "Roll: 270, Pitch: 180, Yaw: 0"]
2375 MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32,
2376 #[doc = "Roll: 90, Pitch: 270, Yaw: 0"]
2377 MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33,
2378 #[doc = "Roll: 180, Pitch: 270, Yaw: 0"]
2379 MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34,
2380 #[doc = "Roll: 270, Pitch: 270, Yaw: 0"]
2381 MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35,
2382 #[doc = "Roll: 90, Pitch: 180, Yaw: 90"]
2383 MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36,
2384 #[doc = "Roll: 90, Pitch: 0, Yaw: 270"]
2385 MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37,
2386 #[doc = "Roll: 90, Pitch: 68, Yaw: 293"]
2387 MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293 = 38,
2388 #[doc = "Pitch: 315"]
2389 MAV_SENSOR_ROTATION_PITCH_315 = 39,
2390 #[doc = "Roll: 90, Pitch: 315"]
2391 MAV_SENSOR_ROTATION_ROLL_90_PITCH_315 = 40,
2392 #[doc = "Custom orientation"]
2393 MAV_SENSOR_ROTATION_CUSTOM = 100,
2394}
2395impl MavSensorOrientation {
2396 pub const DEFAULT: Self = Self::MAV_SENSOR_ROTATION_NONE;
2397}
2398impl Default for MavSensorOrientation {
2399 fn default() -> Self {
2400 Self::DEFAULT
2401 }
2402}
2403#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2404#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2405#[cfg_attr(feature = "serde", serde(tag = "type"))]
2406#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2407#[repr(u32)]
2408#[doc = "Specifies the datatype of a MAVLink extended parameter."]
2409pub enum MavParamExtType {
2410 #[doc = "8-bit unsigned integer"]
2411 MAV_PARAM_EXT_TYPE_UINT8 = 1,
2412 #[doc = "8-bit signed integer"]
2413 MAV_PARAM_EXT_TYPE_INT8 = 2,
2414 #[doc = "16-bit unsigned integer"]
2415 MAV_PARAM_EXT_TYPE_UINT16 = 3,
2416 #[doc = "16-bit signed integer"]
2417 MAV_PARAM_EXT_TYPE_INT16 = 4,
2418 #[doc = "32-bit unsigned integer"]
2419 MAV_PARAM_EXT_TYPE_UINT32 = 5,
2420 #[doc = "32-bit signed integer"]
2421 MAV_PARAM_EXT_TYPE_INT32 = 6,
2422 #[doc = "64-bit unsigned integer"]
2423 MAV_PARAM_EXT_TYPE_UINT64 = 7,
2424 #[doc = "64-bit signed integer"]
2425 MAV_PARAM_EXT_TYPE_INT64 = 8,
2426 #[doc = "32-bit floating-point"]
2427 MAV_PARAM_EXT_TYPE_REAL32 = 9,
2428 #[doc = "64-bit floating-point"]
2429 MAV_PARAM_EXT_TYPE_REAL64 = 10,
2430 #[doc = "Custom Type"]
2431 MAV_PARAM_EXT_TYPE_CUSTOM = 11,
2432}
2433impl MavParamExtType {
2434 pub const DEFAULT: Self = Self::MAV_PARAM_EXT_TYPE_UINT8;
2435}
2436impl Default for MavParamExtType {
2437 fn default() -> Self {
2438 Self::DEFAULT
2439 }
2440}
2441#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2442#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2443#[cfg_attr(feature = "serde", serde(tag = "type"))]
2444#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2445#[repr(u32)]
2446#[doc = "Generalized UAVCAN node health"]
2447pub enum UavcanNodeHealth {
2448 #[doc = "The node is functioning properly."]
2449 UAVCAN_NODE_HEALTH_OK = 0,
2450 #[doc = "A critical parameter went out of range or the node has encountered a minor failure."]
2451 UAVCAN_NODE_HEALTH_WARNING = 1,
2452 #[doc = "The node has encountered a major failure."]
2453 UAVCAN_NODE_HEALTH_ERROR = 2,
2454 #[doc = "The node has suffered a fatal malfunction."]
2455 UAVCAN_NODE_HEALTH_CRITICAL = 3,
2456}
2457impl UavcanNodeHealth {
2458 pub const DEFAULT: Self = Self::UAVCAN_NODE_HEALTH_OK;
2459}
2460impl Default for UavcanNodeHealth {
2461 fn default() -> Self {
2462 Self::DEFAULT
2463 }
2464}
2465#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2466#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2467#[cfg_attr(feature = "serde", serde(tag = "type"))]
2468#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2469#[repr(u32)]
2470#[doc = "Supported component metadata types. These are used in the \"general\" metadata file returned by COMPONENT_METADATA to provide information about supported metadata types. The types are not used directly in MAVLink messages."]
2471pub enum CompMetadataType {
2472 #[doc = "General information about the component. General metadata includes information about other metadata types supported by the component. Files of this type must be supported, and must be downloadable from vehicle using a MAVLink FTP URI."]
2473 COMP_METADATA_TYPE_GENERAL = 0,
2474 #[doc = "Parameter meta data."]
2475 COMP_METADATA_TYPE_PARAMETER = 1,
2476 #[doc = "Meta data that specifies which commands and command parameters the vehicle supports. (WIP)"]
2477 COMP_METADATA_TYPE_COMMANDS = 2,
2478 #[doc = "Meta data that specifies external non-MAVLink peripherals."]
2479 COMP_METADATA_TYPE_PERIPHERALS = 3,
2480 #[doc = "Meta data for the events interface."]
2481 COMP_METADATA_TYPE_EVENTS = 4,
2482 #[doc = "Meta data for actuator configuration (motors, servos and vehicle geometry) and testing."]
2483 COMP_METADATA_TYPE_ACTUATORS = 5,
2484}
2485impl CompMetadataType {
2486 pub const DEFAULT: Self = Self::COMP_METADATA_TYPE_GENERAL;
2487}
2488impl Default for CompMetadataType {
2489 fn default() -> Self {
2490 Self::DEFAULT
2491 }
2492}
2493#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2494#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2495#[cfg_attr(feature = "serde", serde(tag = "type"))]
2496#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2497#[repr(u32)]
2498#[doc = "Enumeration of battery functions"]
2499pub enum MavBatteryFunction {
2500 #[doc = "Battery function is unknown"]
2501 MAV_BATTERY_FUNCTION_UNKNOWN = 0,
2502 #[doc = "Battery supports all flight systems"]
2503 MAV_BATTERY_FUNCTION_ALL = 1,
2504 #[doc = "Battery for the propulsion system"]
2505 MAV_BATTERY_FUNCTION_PROPULSION = 2,
2506 #[doc = "Avionics battery"]
2507 MAV_BATTERY_FUNCTION_AVIONICS = 3,
2508 #[doc = "Payload battery"]
2509 MAV_BATTERY_FUNCTION_PAYLOAD = 4,
2510}
2511impl MavBatteryFunction {
2512 pub const DEFAULT: Self = Self::MAV_BATTERY_FUNCTION_UNKNOWN;
2513}
2514impl Default for MavBatteryFunction {
2515 fn default() -> Self {
2516 Self::DEFAULT
2517 }
2518}
2519bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags used in HIL_ACTUATOR_CONTROLS message."] pub struct HilActuatorControlsFlags : u64 { # [doc = "Simulation is using lockstep"] const HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP = 1 ; } }
2520impl HilActuatorControlsFlags {
2521 pub const DEFAULT: Self = Self::HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP;
2522}
2523impl Default for HilActuatorControlsFlags {
2524 fn default() -> Self {
2525 Self::DEFAULT
2526 }
2527}
2528bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in the HIGHRES_IMU message indicate which fields have updated since the last message"] pub struct HighresImuUpdatedFlags : u16 { # [doc = "The value in the xacc field has been updated"] const HIGHRES_IMU_UPDATED_XACC = 1 ; # [doc = "The value in the yacc field has been updated"] const HIGHRES_IMU_UPDATED_YACC = 2 ; # [doc = "The value in the zacc field has been updated since"] const HIGHRES_IMU_UPDATED_ZACC = 4 ; # [doc = "The value in the xgyro field has been updated"] const HIGHRES_IMU_UPDATED_XGYRO = 8 ; # [doc = "The value in the ygyro field has been updated"] const HIGHRES_IMU_UPDATED_YGYRO = 16 ; # [doc = "The value in the zgyro field has been updated"] const HIGHRES_IMU_UPDATED_ZGYRO = 32 ; # [doc = "The value in the xmag field has been updated"] const HIGHRES_IMU_UPDATED_XMAG = 64 ; # [doc = "The value in the ymag field has been updated"] const HIGHRES_IMU_UPDATED_YMAG = 128 ; # [doc = "The value in the zmag field has been updated"] const HIGHRES_IMU_UPDATED_ZMAG = 256 ; # [doc = "The value in the abs_pressure field has been updated"] const HIGHRES_IMU_UPDATED_ABS_PRESSURE = 512 ; # [doc = "The value in the diff_pressure field has been updated"] const HIGHRES_IMU_UPDATED_DIFF_PRESSURE = 1024 ; # [doc = "The value in the pressure_alt field has been updated"] const HIGHRES_IMU_UPDATED_PRESSURE_ALT = 2048 ; # [doc = "The value in the temperature field has been updated"] const HIGHRES_IMU_UPDATED_TEMPERATURE = 4096 ; } }
2529impl HighresImuUpdatedFlags {
2530 pub const DEFAULT: Self = Self::HIGHRES_IMU_UPDATED_XACC;
2531}
2532impl Default for HighresImuUpdatedFlags {
2533 fn default() -> Self {
2534 Self::DEFAULT
2535 }
2536}
2537#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2538#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2539#[cfg_attr(feature = "serde", serde(tag = "type"))]
2540#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2541#[repr(u32)]
2542pub enum MavState {
2543 #[doc = "Uninitialized system, state is unknown."]
2544 MAV_STATE_UNINIT = 0,
2545 #[doc = "System is booting up."]
2546 MAV_STATE_BOOT = 1,
2547 #[doc = "System is calibrating and not flight-ready."]
2548 MAV_STATE_CALIBRATING = 2,
2549 #[doc = "System is grounded and on standby. It can be launched any time."]
2550 MAV_STATE_STANDBY = 3,
2551 #[doc = "System is active and might be already airborne. Motors are engaged."]
2552 MAV_STATE_ACTIVE = 4,
2553 #[doc = "System is in a non-normal flight mode (failsafe). It can however still navigate."]
2554 MAV_STATE_CRITICAL = 5,
2555 #[doc = "System is in a non-normal flight mode (failsafe). It lost control over parts or over the whole airframe. It is in mayday and going down."]
2556 MAV_STATE_EMERGENCY = 6,
2557 #[doc = "System just initialized its power-down sequence, will shut down now."]
2558 MAV_STATE_POWEROFF = 7,
2559 #[doc = "System is terminating itself (failsafe or commanded)."]
2560 MAV_STATE_FLIGHT_TERMINATION = 8,
2561}
2562impl MavState {
2563 pub const DEFAULT: Self = Self::MAV_STATE_UNINIT;
2564}
2565impl Default for MavState {
2566 fn default() -> Self {
2567 Self::DEFAULT
2568 }
2569}
2570bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal device (low level) capability flags (bitmap)."] pub struct GimbalDeviceCapFlags : u16 { # [doc = "Gimbal device supports a retracted position."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT = 1 ; # [doc = "Gimbal device supports a horizontal, forward looking position, stabilized."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL = 2 ; # [doc = "Gimbal device supports rotating around roll axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS = 4 ; # [doc = "Gimbal device supports to follow a roll angle relative to the vehicle."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 ; # [doc = "Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK = 16 ; # [doc = "Gimbal device supports rotating around pitch axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS = 32 ; # [doc = "Gimbal device supports to follow a pitch angle relative to the vehicle."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 ; # [doc = "Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK = 128 ; # [doc = "Gimbal device supports rotating around yaw axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS = 256 ; # [doc = "Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW = 512 ; # [doc = "Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK = 1024 ; # [doc = "Gimbal device supports yawing/panning infinitely (e.g. using slip disk)."] const GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 ; # [doc = "Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME."] const GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = 4096 ; # [doc = "Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS = 8192 ; } }
2571impl GimbalDeviceCapFlags {
2572 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT;
2573}
2574impl Default for GimbalDeviceCapFlags {
2575 fn default() -> Self {
2576 Self::DEFAULT
2577 }
2578}
2579#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2580#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2581#[cfg_attr(feature = "serde", serde(tag = "type"))]
2582#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2583#[repr(u32)]
2584#[doc = "GPS lataral offset encoding"]
2585pub enum UavionixAdsbOutCfgGpsOffsetLat {
2586 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_NO_DATA = 0,
2587 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_2M = 1,
2588 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_4M = 2,
2589 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_6M = 3,
2590 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_0M = 4,
2591 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_2M = 5,
2592 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_4M = 6,
2593 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_6M = 7,
2594}
2595impl UavionixAdsbOutCfgGpsOffsetLat {
2596 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_NO_DATA;
2597}
2598impl Default for UavionixAdsbOutCfgGpsOffsetLat {
2599 fn default() -> Self {
2600 Self::DEFAULT
2601 }
2602}
2603bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for the global position report."] pub struct UtmDataAvailFlags : u8 { # [doc = "The field time contains valid data."] const UTM_DATA_AVAIL_FLAGS_TIME_VALID = 1 ; # [doc = "The field uas_id contains valid data."] const UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE = 2 ; # [doc = "The fields lat, lon and h_acc contain valid data."] const UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE = 4 ; # [doc = "The fields alt and v_acc contain valid data."] const UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE = 8 ; # [doc = "The field relative_alt contains valid data."] const UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE = 16 ; # [doc = "The fields vx and vy contain valid data."] const UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE = 32 ; # [doc = "The field vz contains valid data."] const UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE = 64 ; # [doc = "The fields next_lat, next_lon and next_alt contain valid data."] const UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE = 128 ; } }
2604impl UtmDataAvailFlags {
2605 pub const DEFAULT: Self = Self::UTM_DATA_AVAIL_FLAGS_TIME_VALID;
2606}
2607impl Default for UtmDataAvailFlags {
2608 fn default() -> Self {
2609 Self::DEFAULT
2610 }
2611}
2612#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2613#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2614#[cfg_attr(feature = "serde", serde(tag = "type"))]
2615#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2616#[repr(u32)]
2617#[doc = "Tune formats (used for vehicle buzzer/tone generation)."]
2618pub enum TuneFormat {
2619 #[doc = "Format is QBasic 1.1 Play: <https://www.qbasic.net/en/reference/qb11/Statement/PLAY-006.htm>."]
2620 TUNE_FORMAT_QBASIC1_1 = 1,
2621 #[doc = "Format is Modern Music Markup Language (MML): <https://en.wikipedia.org/wiki/Music_Macro_Language#Modern_MML>."]
2622 TUNE_FORMAT_MML_MODERN = 2,
2623}
2624impl TuneFormat {
2625 pub const DEFAULT: Self = Self::TUNE_FORMAT_QBASIC1_1;
2626}
2627impl Default for TuneFormat {
2628 fn default() -> Self {
2629 Self::DEFAULT
2630 }
2631}
2632bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE)."] pub struct StorageUsageFlag : u8 { # [doc = "Always set to 1 (indicates STORAGE_INFORMATION.storage_usage is supported)."] const STORAGE_USAGE_FLAG_SET = 1 ; # [doc = "Storage for saving photos."] const STORAGE_USAGE_FLAG_PHOTO = 2 ; # [doc = "Storage for saving videos."] const STORAGE_USAGE_FLAG_VIDEO = 4 ; # [doc = "Storage for saving logs."] const STORAGE_USAGE_FLAG_LOGS = 8 ; } }
2633impl StorageUsageFlag {
2634 pub const DEFAULT: Self = Self::STORAGE_USAGE_FLAG_SET;
2635}
2636impl Default for StorageUsageFlag {
2637 fn default() -> Self {
2638 Self::DEFAULT
2639 }
2640}
2641bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration."] pub struct PositionTargetTypemask : u16 { # [doc = "Ignore position x"] const POSITION_TARGET_TYPEMASK_X_IGNORE = 1 ; # [doc = "Ignore position y"] const POSITION_TARGET_TYPEMASK_Y_IGNORE = 2 ; # [doc = "Ignore position z"] const POSITION_TARGET_TYPEMASK_Z_IGNORE = 4 ; # [doc = "Ignore velocity x"] const POSITION_TARGET_TYPEMASK_VX_IGNORE = 8 ; # [doc = "Ignore velocity y"] const POSITION_TARGET_TYPEMASK_VY_IGNORE = 16 ; # [doc = "Ignore velocity z"] const POSITION_TARGET_TYPEMASK_VZ_IGNORE = 32 ; # [doc = "Ignore acceleration x"] const POSITION_TARGET_TYPEMASK_AX_IGNORE = 64 ; # [doc = "Ignore acceleration y"] const POSITION_TARGET_TYPEMASK_AY_IGNORE = 128 ; # [doc = "Ignore acceleration z"] const POSITION_TARGET_TYPEMASK_AZ_IGNORE = 256 ; # [doc = "Use force instead of acceleration"] const POSITION_TARGET_TYPEMASK_FORCE_SET = 512 ; # [doc = "Ignore yaw"] const POSITION_TARGET_TYPEMASK_YAW_IGNORE = 1024 ; # [doc = "Ignore yaw rate"] const POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = 2048 ; } }
2642impl PositionTargetTypemask {
2643 pub const DEFAULT: Self = Self::POSITION_TARGET_TYPEMASK_X_IGNORE;
2644}
2645impl Default for PositionTargetTypemask {
2646 fn default() -> Self {
2647 Self::DEFAULT
2648 }
2649}
2650#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2651#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2652#[cfg_attr(feature = "serde", serde(tag = "type"))]
2653#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2654#[repr(u32)]
2655#[doc = "Precision land modes (used in MAV_CMD_NAV_LAND)."]
2656pub enum PrecisionLandMode {
2657 #[doc = "Normal (non-precision) landing."]
2658 PRECISION_LAND_MODE_DISABLED = 0,
2659 #[doc = "Use precision landing if beacon detected when land command accepted, otherwise land normally."]
2660 PRECISION_LAND_MODE_OPPORTUNISTIC = 1,
2661 #[doc = "Use precision landing, searching for beacon if not found when land command accepted (land normally if beacon cannot be found)."]
2662 PRECISION_LAND_MODE_REQUIRED = 2,
2663}
2664impl PrecisionLandMode {
2665 pub const DEFAULT: Self = Self::PRECISION_LAND_MODE_DISABLED;
2666}
2667impl Default for PrecisionLandMode {
2668 fn default() -> Self {
2669 Self::DEFAULT
2670 }
2671}
2672#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2673#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2674#[cfg_attr(feature = "serde", serde(tag = "type"))]
2675#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2676#[repr(u32)]
2677pub enum MavOdidStatus {
2678 #[doc = "The status of the (UA) Unmanned Aircraft is undefined."]
2679 MAV_ODID_STATUS_UNDECLARED = 0,
2680 #[doc = "The UA is on the ground."]
2681 MAV_ODID_STATUS_GROUND = 1,
2682 #[doc = "The UA is in the air."]
2683 MAV_ODID_STATUS_AIRBORNE = 2,
2684 #[doc = "The UA is having an emergency."]
2685 MAV_ODID_STATUS_EMERGENCY = 3,
2686 #[doc = "The remote ID system is failing or unreliable in some way."]
2687 MAV_ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE = 4,
2688}
2689impl MavOdidStatus {
2690 pub const DEFAULT: Self = Self::MAV_ODID_STATUS_UNDECLARED;
2691}
2692impl Default for MavOdidStatus {
2693 fn default() -> Self {
2694 Self::DEFAULT
2695 }
2696}
2697#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2698#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2699#[cfg_attr(feature = "serde", serde(tag = "type"))]
2700#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2701#[repr(u32)]
2702pub enum MavOdidIdType {
2703 #[doc = "No type defined."]
2704 MAV_ODID_ID_TYPE_NONE = 0,
2705 #[doc = "Manufacturer Serial Number (ANSI/CTA-2063 format)."]
2706 MAV_ODID_ID_TYPE_SERIAL_NUMBER = 1,
2707 #[doc = "CAA (Civil Aviation Authority) registered ID. Format: [ICAO Country Code].[CAA Assigned ID]."]
2708 MAV_ODID_ID_TYPE_CAA_REGISTRATION_ID = 2,
2709 #[doc = "UTM (Unmanned Traffic Management) assigned UUID (RFC4122)."]
2710 MAV_ODID_ID_TYPE_UTM_ASSIGNED_UUID = 3,
2711 #[doc = "A 20 byte ID for a specific flight/session. The exact ID type is indicated by the first byte of uas_id and these type values are managed by ICAO."]
2712 MAV_ODID_ID_TYPE_SPECIFIC_SESSION_ID = 4,
2713}
2714impl MavOdidIdType {
2715 pub const DEFAULT: Self = Self::MAV_ODID_ID_TYPE_NONE;
2716}
2717impl Default for MavOdidIdType {
2718 fn default() -> Self {
2719 Self::DEFAULT
2720 }
2721}
2722#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2723#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2724#[cfg_attr(feature = "serde", serde(tag = "type"))]
2725#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2726#[repr(u32)]
2727#[doc = "Yaw behaviour during orbit flight."]
2728pub enum OrbitYawBehaviour {
2729 #[doc = "Vehicle front points to the center (default)."]
2730 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER = 0,
2731 #[doc = "Vehicle front holds heading when message received."]
2732 ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1,
2733 #[doc = "Yaw uncontrolled."]
2734 ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2,
2735 #[doc = "Vehicle front follows flight path (tangential to circle)."]
2736 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3,
2737 #[doc = "Yaw controlled by RC input."]
2738 ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4,
2739 #[doc = "Vehicle uses current yaw behaviour (unchanged). The vehicle-default yaw behaviour is used if this value is specified when orbit is first commanded."]
2740 ORBIT_YAW_BEHAVIOUR_UNCHANGED = 5,
2741}
2742impl OrbitYawBehaviour {
2743 pub const DEFAULT: Self = Self::ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER;
2744}
2745impl Default for OrbitYawBehaviour {
2746 fn default() -> Self {
2747 Self::DEFAULT
2748 }
2749}
2750bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags encode the MAV mode."] pub struct MavModeFlag : u8 { # [doc = "0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state."] const MAV_MODE_FLAG_SAFETY_ARMED = 128 ; # [doc = "0b01000000 remote control input is enabled."] const MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 ; # [doc = "0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational."] const MAV_MODE_FLAG_HIL_ENABLED = 32 ; # [doc = "0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around."] const MAV_MODE_FLAG_STABILIZE_ENABLED = 16 ; # [doc = "0b00001000 guided mode enabled, system flies waypoints / mission items."] const MAV_MODE_FLAG_GUIDED_ENABLED = 8 ; # [doc = "0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation."] const MAV_MODE_FLAG_AUTO_ENABLED = 4 ; # [doc = "0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations."] const MAV_MODE_FLAG_TEST_ENABLED = 2 ; # [doc = "0b00000001 Reserved for future use."] const MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 ; } }
2751impl MavModeFlag {
2752 pub const DEFAULT: Self = Self::MAV_MODE_FLAG_SAFETY_ARMED;
2753}
2754impl Default for MavModeFlag {
2755 fn default() -> Self {
2756 Self::DEFAULT
2757 }
2758}
2759#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2760#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2761#[cfg_attr(feature = "serde", serde(tag = "type"))]
2762#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2763#[repr(u32)]
2764#[doc = "Generalized UAVCAN node mode"]
2765pub enum UavcanNodeMode {
2766 #[doc = "The node is performing its primary functions."]
2767 UAVCAN_NODE_MODE_OPERATIONAL = 0,
2768 #[doc = "The node is initializing; this mode is entered immediately after startup."]
2769 UAVCAN_NODE_MODE_INITIALIZATION = 1,
2770 #[doc = "The node is under maintenance."]
2771 UAVCAN_NODE_MODE_MAINTENANCE = 2,
2772 #[doc = "The node is in the process of updating its software."]
2773 UAVCAN_NODE_MODE_SOFTWARE_UPDATE = 3,
2774 #[doc = "The node is no longer available online."]
2775 UAVCAN_NODE_MODE_OFFLINE = 7,
2776}
2777impl UavcanNodeMode {
2778 pub const DEFAULT: Self = Self::UAVCAN_NODE_MODE_OPERATIONAL;
2779}
2780impl Default for UavcanNodeMode {
2781 fn default() -> Self {
2782 Self::DEFAULT
2783 }
2784}
2785#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2786#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2787#[cfg_attr(feature = "serde", serde(tag = "type"))]
2788#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2789#[repr(u32)]
2790pub enum MavTunnelPayloadType {
2791 #[doc = "Encoding of payload unknown."]
2792 MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN = 0,
2793 #[doc = "Registered for STorM32 gimbal controller."]
2794 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED0 = 200,
2795 #[doc = "Registered for STorM32 gimbal controller."]
2796 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED1 = 201,
2797 #[doc = "Registered for STorM32 gimbal controller."]
2798 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED2 = 202,
2799 #[doc = "Registered for STorM32 gimbal controller."]
2800 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED3 = 203,
2801 #[doc = "Registered for STorM32 gimbal controller."]
2802 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED4 = 204,
2803 #[doc = "Registered for STorM32 gimbal controller."]
2804 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED5 = 205,
2805 #[doc = "Registered for STorM32 gimbal controller."]
2806 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6 = 206,
2807 #[doc = "Registered for STorM32 gimbal controller."]
2808 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7 = 207,
2809 #[doc = "Registered for STorM32 gimbal controller."]
2810 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8 = 208,
2811 #[doc = "Registered for STorM32 gimbal controller."]
2812 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9 = 209,
2813 #[doc = "Registered for ModalAI remote OSD protocol."]
2814 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_REMOTE_OSD = 210,
2815 #[doc = "Registered for ModalAI ESC UART passthru protocol."]
2816 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_ESC_UART_PASSTHRU = 211,
2817 #[doc = "Registered for ModalAI vendor use."]
2818 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_IO_UART_PASSTHRU = 212,
2819}
2820impl MavTunnelPayloadType {
2821 pub const DEFAULT: Self = Self::MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN;
2822}
2823impl Default for MavTunnelPayloadType {
2824 fn default() -> Self {
2825 Self::DEFAULT
2826 }
2827}
2828#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2829#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2830#[cfg_attr(feature = "serde", serde(tag = "type"))]
2831#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2832#[repr(u32)]
2833#[doc = "Result from a MAVLink command (MAV_CMD)"]
2834pub enum MavResult {
2835 #[doc = "Command is valid (is supported and has valid parameters), and was executed."]
2836 MAV_RESULT_ACCEPTED = 0,
2837 #[doc = "Command is valid, but cannot be executed at this time. This is used to indicate a problem that should be fixed just by waiting (e.g. a state machine is busy, can't arm because have not got GPS lock, etc.). Retrying later should work."]
2838 MAV_RESULT_TEMPORARILY_REJECTED = 1,
2839 #[doc = "Command is invalid (is supported but has invalid parameters). Retrying same command and parameters will not work."]
2840 MAV_RESULT_DENIED = 2,
2841 #[doc = "Command is not supported (unknown)."]
2842 MAV_RESULT_UNSUPPORTED = 3,
2843 #[doc = "Command is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc."]
2844 MAV_RESULT_FAILED = 4,
2845 #[doc = "Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation."]
2846 MAV_RESULT_IN_PROGRESS = 5,
2847 #[doc = "Command has been cancelled (as a result of receiving a COMMAND_CANCEL message)."]
2848 MAV_RESULT_CANCELLED = 6,
2849 #[doc = "Command is only accepted when sent as a COMMAND_LONG."]
2850 MAV_RESULT_COMMAND_LONG_ONLY = 7,
2851 #[doc = "Command is only accepted when sent as a COMMAND_INT."]
2852 MAV_RESULT_COMMAND_INT_ONLY = 8,
2853 #[doc = "Command is invalid because a frame is required and the specified frame is not supported."]
2854 MAV_RESULT_COMMAND_UNSUPPORTED_MAV_FRAME = 9,
2855}
2856impl MavResult {
2857 pub const DEFAULT: Self = Self::MAV_RESULT_ACCEPTED;
2858}
2859impl Default for MavResult {
2860 fn default() -> Self {
2861 Self::DEFAULT
2862 }
2863}
2864#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2865#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2866#[cfg_attr(feature = "serde", serde(tag = "type"))]
2867#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2868#[repr(u32)]
2869#[doc = "Possible responses from a CELLULAR_CONFIG message."]
2870pub enum CellularConfigResponse {
2871 #[doc = "Changes accepted."]
2872 CELLULAR_CONFIG_RESPONSE_ACCEPTED = 0,
2873 #[doc = "Invalid APN."]
2874 CELLULAR_CONFIG_RESPONSE_APN_ERROR = 1,
2875 #[doc = "Invalid PIN."]
2876 CELLULAR_CONFIG_RESPONSE_PIN_ERROR = 2,
2877 #[doc = "Changes rejected."]
2878 CELLULAR_CONFIG_RESPONSE_REJECTED = 3,
2879 #[doc = "PUK is required to unblock SIM card."]
2880 CELLULAR_CONFIG_BLOCKED_PUK_REQUIRED = 4,
2881}
2882impl CellularConfigResponse {
2883 pub const DEFAULT: Self = Self::CELLULAR_CONFIG_RESPONSE_ACCEPTED;
2884}
2885impl Default for CellularConfigResponse {
2886 fn default() -> Self {
2887 Self::DEFAULT
2888 }
2889}
2890bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report failure cases over the high latency telemetry."] pub struct HlFailureFlag : u16 { # [doc = "GPS failure."] const HL_FAILURE_FLAG_GPS = 1 ; # [doc = "Differential pressure sensor failure."] const HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE = 2 ; # [doc = "Absolute pressure sensor failure."] const HL_FAILURE_FLAG_ABSOLUTE_PRESSURE = 4 ; # [doc = "Accelerometer sensor failure."] const HL_FAILURE_FLAG_3D_ACCEL = 8 ; # [doc = "Gyroscope sensor failure."] const HL_FAILURE_FLAG_3D_GYRO = 16 ; # [doc = "Magnetometer sensor failure."] const HL_FAILURE_FLAG_3D_MAG = 32 ; # [doc = "Terrain subsystem failure."] const HL_FAILURE_FLAG_TERRAIN = 64 ; # [doc = "Battery failure/critical low battery."] const HL_FAILURE_FLAG_BATTERY = 128 ; # [doc = "RC receiver failure/no RC connection."] const HL_FAILURE_FLAG_RC_RECEIVER = 256 ; # [doc = "Offboard link failure."] const HL_FAILURE_FLAG_OFFBOARD_LINK = 512 ; # [doc = "Engine failure."] const HL_FAILURE_FLAG_ENGINE = 1024 ; # [doc = "Geofence violation."] const HL_FAILURE_FLAG_GEOFENCE = 2048 ; # [doc = "Estimator failure, for example measurement rejection or large variances."] const HL_FAILURE_FLAG_ESTIMATOR = 4096 ; # [doc = "Mission failure."] const HL_FAILURE_FLAG_MISSION = 8192 ; } }
2891impl HlFailureFlag {
2892 pub const DEFAULT: Self = Self::HL_FAILURE_FLAG_GPS;
2893}
2894impl Default for HlFailureFlag {
2895 fn default() -> Self {
2896 Self::DEFAULT
2897 }
2898}
2899bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These encode the sensors whose status is sent as part of the SYS_STATUS message."] pub struct MavSysStatusSensor : u32 { # [doc = "0x01 3D gyro"] const MAV_SYS_STATUS_SENSOR_3D_GYRO = 1 ; # [doc = "0x02 3D accelerometer"] const MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2 ; # [doc = "0x04 3D magnetometer"] const MAV_SYS_STATUS_SENSOR_3D_MAG = 4 ; # [doc = "0x08 absolute pressure"] const MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8 ; # [doc = "0x10 differential pressure"] const MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16 ; # [doc = "0x20 GPS"] const MAV_SYS_STATUS_SENSOR_GPS = 32 ; # [doc = "0x40 optical flow"] const MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64 ; # [doc = "0x80 computer vision position"] const MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128 ; # [doc = "0x100 laser based position"] const MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256 ; # [doc = "0x200 external ground truth (Vicon or Leica)"] const MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512 ; # [doc = "0x400 3D angular rate control"] const MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024 ; # [doc = "0x800 attitude stabilization"] const MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048 ; # [doc = "0x1000 yaw position"] const MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096 ; # [doc = "0x2000 z/altitude control"] const MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192 ; # [doc = "0x4000 x/y position control"] const MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384 ; # [doc = "0x8000 motor outputs / control"] const MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768 ; # [doc = "0x10000 RC receiver"] const MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536 ; # [doc = "0x20000 2nd 3D gyro"] const MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072 ; # [doc = "0x40000 2nd 3D accelerometer"] const MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144 ; # [doc = "0x80000 2nd 3D magnetometer"] const MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288 ; # [doc = "0x100000 geofence"] const MAV_SYS_STATUS_GEOFENCE = 1048576 ; # [doc = "0x200000 AHRS subsystem health"] const MAV_SYS_STATUS_AHRS = 2097152 ; # [doc = "0x400000 Terrain subsystem health"] const MAV_SYS_STATUS_TERRAIN = 4194304 ; # [doc = "0x800000 Motors are reversed"] const MAV_SYS_STATUS_REVERSE_MOTOR = 8388608 ; # [doc = "0x1000000 Logging"] const MAV_SYS_STATUS_LOGGING = 16777216 ; # [doc = "0x2000000 Battery"] const MAV_SYS_STATUS_SENSOR_BATTERY = 33554432 ; # [doc = "0x4000000 Proximity"] const MAV_SYS_STATUS_SENSOR_PROXIMITY = 67108864 ; # [doc = "0x8000000 Satellite Communication"] const MAV_SYS_STATUS_SENSOR_SATCOM = 134217728 ; # [doc = "0x10000000 pre-arm check status. Always healthy when armed"] const MAV_SYS_STATUS_PREARM_CHECK = 268435456 ; # [doc = "0x20000000 Avoidance/collision prevention"] const MAV_SYS_STATUS_OBSTACLE_AVOIDANCE = 536870912 ; # [doc = "0x40000000 propulsion (actuator, esc, motor or propellor)"] const MAV_SYS_STATUS_SENSOR_PROPULSION = 1073741824 ; # [doc = "0x80000000 Extended bit-field are used for further sensor status bits (needs to be set in onboard_control_sensors_present only)"] const MAV_SYS_STATUS_EXTENSION_USED = 2147483648 ; } }
2900impl MavSysStatusSensor {
2901 pub const DEFAULT: Self = Self::MAV_SYS_STATUS_SENSOR_3D_GYRO;
2902}
2903impl Default for MavSysStatusSensor {
2904 fn default() -> Self {
2905 Self::DEFAULT
2906 }
2907}
2908#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2909#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2910#[cfg_attr(feature = "serde", serde(tag = "type"))]
2911#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2912#[repr(u32)]
2913#[doc = "Actions for reading and writing plan information (mission, rally points, geofence) between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly missions are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)"]
2914pub enum PreflightStorageMissionAction {
2915 #[doc = "Read current mission data from persistent storage"]
2916 MISSION_READ_PERSISTENT = 0,
2917 #[doc = "Write current mission data to persistent storage"]
2918 MISSION_WRITE_PERSISTENT = 1,
2919 #[doc = "Erase all mission data stored on the vehicle (both persistent and volatile storage)"]
2920 MISSION_RESET_DEFAULT = 2,
2921}
2922impl PreflightStorageMissionAction {
2923 pub const DEFAULT: Self = Self::MISSION_READ_PERSISTENT;
2924}
2925impl Default for PreflightStorageMissionAction {
2926 fn default() -> Self {
2927 Self::DEFAULT
2928 }
2929}
2930#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2931#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2932#[cfg_attr(feature = "serde", serde(tag = "type"))]
2933#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2934#[repr(u32)]
2935#[doc = "Fuel types for use in FUEL_TYPE. Fuel types specify the units for the maximum, available and consumed fuel, and for the flow rates."]
2936pub enum MavFuelType {
2937 #[doc = "Not specified. Fuel levels are normalized (i.e. maximum is 1, and other levels are relative to 1)."]
2938 MAV_FUEL_TYPE_UNKNOWN = 0,
2939 #[doc = "A generic liquid fuel. Fuel levels are in millilitres (ml). Fuel rates are in millilitres/second."]
2940 MAV_FUEL_TYPE_LIQUID = 1,
2941 #[doc = "A gas tank. Fuel levels are in kilo-Pascal (kPa), and flow rates are in milliliters per second (ml/s)."]
2942 MAV_FUEL_TYPE_GAS = 2,
2943}
2944impl MavFuelType {
2945 pub const DEFAULT: Self = Self::MAV_FUEL_TYPE_UNKNOWN;
2946}
2947impl Default for MavFuelType {
2948 fn default() -> Self {
2949 Self::DEFAULT
2950 }
2951}
2952#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2953#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2954#[cfg_attr(feature = "serde", serde(tag = "type"))]
2955#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2956#[repr(u32)]
2957#[doc = "Camera Modes."]
2958pub enum CameraMode {
2959 #[doc = "Camera is in image/photo capture mode."]
2960 CAMERA_MODE_IMAGE = 0,
2961 #[doc = "Camera is in video capture mode."]
2962 CAMERA_MODE_VIDEO = 1,
2963 #[doc = "Camera is in image survey capture mode. It allows for camera controller to do specific settings for surveys."]
2964 CAMERA_MODE_IMAGE_SURVEY = 2,
2965}
2966impl CameraMode {
2967 pub const DEFAULT: Self = Self::CAMERA_MODE_IMAGE;
2968}
2969impl Default for CameraMode {
2970 fn default() -> Self {
2971 Self::DEFAULT
2972 }
2973}
2974#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2975#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2976#[cfg_attr(feature = "serde", serde(tag = "type"))]
2977#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2978#[repr(u32)]
2979#[doc = "Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See <https://mavlink.io/en/guide/xml_schema.html#MAV_CMD> for information about the structure of the MAV_CMD entries"]
2980pub enum MavCmd {
2981 #[doc = "Navigate to waypoint. This is intended for use in missions (for guided commands outside of missions use MAV_CMD_DO_REPOSITION)."]
2982 MAV_CMD_NAV_WAYPOINT = 16,
2983 #[doc = "Loiter around this waypoint an unlimited amount of time"]
2984 MAV_CMD_NAV_LOITER_UNLIM = 17,
2985 #[doc = "Loiter around this waypoint for X turns"]
2986 MAV_CMD_NAV_LOITER_TURNS = 18,
2987 #[doc = "Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint."]
2988 MAV_CMD_NAV_LOITER_TIME = 19,
2989 #[doc = "Return to launch location"]
2990 MAV_CMD_NAV_RETURN_TO_LAUNCH = 20,
2991 #[doc = "Land at location."]
2992 MAV_CMD_NAV_LAND = 21,
2993 #[doc = "Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode."]
2994 MAV_CMD_NAV_TAKEOFF = 22,
2995 #[doc = "Land at local position (local frame only)"]
2996 MAV_CMD_NAV_LAND_LOCAL = 23,
2997 #[doc = "Takeoff from local position (local frame only)"]
2998 MAV_CMD_NAV_TAKEOFF_LOCAL = 24,
2999 #[doc = "Vehicle following, i.e. this waypoint represents the position of a moving vehicle"]
3000 MAV_CMD_NAV_FOLLOW = 25,
3001 #[doc = "Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached."]
3002 MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30,
3003 #[doc = "Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint."]
3004 MAV_CMD_NAV_LOITER_TO_ALT = 31,
3005 #[doc = "Begin following a target"]
3006 MAV_CMD_DO_FOLLOW = 32,
3007 #[doc = "Reposition the MAV after a follow target command has been sent"]
3008 MAV_CMD_DO_FOLLOW_REPOSITION = 33,
3009 #[doc = "Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults."]
3010 MAV_CMD_DO_ORBIT = 34,
3011 #[doc = "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."]
3012 MAV_CMD_NAV_ROI = 80,
3013 #[doc = "Control autonomous path planning on the MAV."]
3014 MAV_CMD_NAV_PATHPLANNING = 81,
3015 #[doc = "Navigate to waypoint using a spline path."]
3016 MAV_CMD_NAV_SPLINE_WAYPOINT = 82,
3017 #[doc = "Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.)."]
3018 MAV_CMD_NAV_VTOL_TAKEOFF = 84,
3019 #[doc = "Land using VTOL mode"]
3020 MAV_CMD_NAV_VTOL_LAND = 85,
3021 #[doc = "hand control over to an external controller"]
3022 MAV_CMD_NAV_GUIDED_ENABLE = 92,
3023 #[doc = "Delay the next navigation command a number of seconds or until a specified time"]
3024 MAV_CMD_NAV_DELAY = 93,
3025 #[doc = "Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload."]
3026 MAV_CMD_NAV_PAYLOAD_PLACE = 94,
3027 #[doc = "NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration"]
3028 MAV_CMD_NAV_LAST = 95,
3029 #[doc = "Delay mission state machine."]
3030 MAV_CMD_CONDITION_DELAY = 112,
3031 #[doc = "Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached."]
3032 MAV_CMD_CONDITION_CHANGE_ALT = 113,
3033 #[doc = "Delay mission state machine until within desired distance of next NAV point."]
3034 MAV_CMD_CONDITION_DISTANCE = 114,
3035 #[doc = "Reach a certain target angle."]
3036 MAV_CMD_CONDITION_YAW = 115,
3037 #[doc = "NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration"]
3038 MAV_CMD_CONDITION_LAST = 159,
3039 #[doc = "Set system mode."]
3040 MAV_CMD_DO_SET_MODE = 176,
3041 #[doc = "Jump to the desired command in the mission list. Repeat this action only the specified number of times"]
3042 MAV_CMD_DO_JUMP = 177,
3043 #[doc = "Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change"]
3044 MAV_CMD_DO_CHANGE_SPEED = 178,
3045 #[doc = "Sets the home position to either to the current position or a specified position. The home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this command). Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)."]
3046 MAV_CMD_DO_SET_HOME = 179,
3047 #[doc = "Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter."]
3048 MAV_CMD_DO_SET_PARAMETER = 180,
3049 #[doc = "Set a relay to a condition."]
3050 MAV_CMD_DO_SET_RELAY = 181,
3051 #[doc = "Cycle a relay on and off for a desired number of cycles with a desired period."]
3052 MAV_CMD_DO_REPEAT_RELAY = 182,
3053 #[doc = "Set a servo to a desired PWM value."]
3054 MAV_CMD_DO_SET_SERVO = 183,
3055 #[doc = "Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period."]
3056 MAV_CMD_DO_REPEAT_SERVO = 184,
3057 #[doc = "0.5); the ACK should be either MAV_RESULT_FAILED or MAV_RESULT_UNSUPPORTED."]
3058 MAV_CMD_DO_FLIGHTTERMINATION = 185,
3059 #[doc = "Change altitude set point."]
3060 MAV_CMD_DO_CHANGE_ALTITUDE = 186,
3061 #[doc = "Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter)."]
3062 MAV_CMD_DO_SET_ACTUATOR = 187,
3063 #[doc = "Mission item to specify the start of a failsafe/landing return-path segment (the end of the segment is the next MAV_CMD_DO_LAND_START item). A vehicle that is using missions for landing (e.g. in a return mode) will join the mission on the closest path of the return-path segment (instead of MAV_CMD_DO_LAND_START or the nearest waypoint). The main use case is to minimize the failsafe flight path in corridor missions, where the inbound/outbound paths are constrained (by geofences) to the same particular path. The MAV_CMD_NAV_RETURN_PATH_START would be placed at the start of the return path. If a failsafe occurs on the outbound path the vehicle will move to the nearest point on the return path (which is parallel for this kind of mission), effectively turning round and following the shortest path to landing. If a failsafe occurs on the inbound path the vehicle is already on the return segment and will continue to landing. The Latitude/Longitude/Altitude are optional, and may be set to 0 if not needed. If specified, the item defines the waypoint at which the return segment starts. If sent using as a command, the vehicle will perform a mission landing (using the land segment if defined) or reject the command if mission landings are not supported, or no mission landing is defined. When used as a command any position information in the command is ignored."]
3064 MAV_CMD_DO_RETURN_PATH_START = 188,
3065 #[doc = "Mission item to mark the start of a mission landing pattern, or a command to land with a mission landing pattern. When used in a mission, this is a marker for the start of a sequence of mission items that represent a landing pattern. It should be followed by a navigation item that defines the first waypoint of the landing sequence. The start marker positional params are used only for selecting what landing pattern to use if several are defined in the mission (the selected pattern will be the one with the marker position that is closest to the vehicle when a landing is commanded). If the marker item position has zero-values for latitude, longitude, and altitude, then landing pattern selection is instead based on the position of the first waypoint in the landing sequence. \t When sent as a command it triggers a landing using a mission landing pattern. \t The location parameters are not used in this case, and should be set to 0."]
3066 MAV_CMD_DO_LAND_START = 189,
3067 #[doc = "Mission command to perform a landing from a rally point."]
3068 MAV_CMD_DO_RALLY_LAND = 190,
3069 #[doc = "Mission command to safely abort an autonomous landing."]
3070 MAV_CMD_DO_GO_AROUND = 191,
3071 #[doc = "Reposition the vehicle to a specific WGS84 global position. This command is intended for guided commands (for missions use MAV_CMD_NAV_WAYPOINT instead)."]
3072 MAV_CMD_DO_REPOSITION = 192,
3073 #[doc = "If in a GPS controlled position mode, hold the current position or continue."]
3074 MAV_CMD_DO_PAUSE_CONTINUE = 193,
3075 #[doc = "Set moving direction to forward or reverse."]
3076 MAV_CMD_DO_SET_REVERSE = 194,
3077 #[doc = "Sets the region of interest (ROI) to a location. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message."]
3078 MAV_CMD_DO_SET_ROI_LOCATION = 195,
3079 #[doc = "Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message."]
3080 MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196,
3081 #[doc = "Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position."]
3082 MAV_CMD_DO_SET_ROI_NONE = 197,
3083 #[doc = "Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message."]
3084 MAV_CMD_DO_SET_ROI_SYSID = 198,
3085 #[doc = "Control onboard camera system."]
3086 MAV_CMD_DO_CONTROL_VIDEO = 200,
3087 #[doc = "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."]
3088 MAV_CMD_DO_SET_ROI = 201,
3089 #[doc = "Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see <https://mavlink.io/en/services/camera_def.html> )."]
3090 MAV_CMD_DO_DIGICAM_CONFIGURE = 202,
3091 #[doc = "Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see <https://mavlink.io/en/services/camera_def.html> )."]
3092 MAV_CMD_DO_DIGICAM_CONTROL = 203,
3093 #[doc = "Mission command to configure a camera or antenna mount"]
3094 MAV_CMD_DO_MOUNT_CONFIGURE = 204,
3095 #[doc = "Mission command to control a camera or antenna mount"]
3096 MAV_CMD_DO_MOUNT_CONTROL = 205,
3097 #[doc = "Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera."]
3098 MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206,
3099 #[doc = "Enable the geofence. This can be used in a mission or via the command protocol. The persistence/lifetime of the setting is undefined. Depending on flight stack implementation it may persist until superseded, or it may revert to a system default at the end of a mission. Flight stacks typically reset the setting to system defaults on reboot."]
3100 MAV_CMD_DO_FENCE_ENABLE = 207,
3101 #[doc = "Mission item/command to release a parachute or enable/disable auto release."]
3102 MAV_CMD_DO_PARACHUTE = 208,
3103 #[doc = "Command to perform motor test."]
3104 MAV_CMD_DO_MOTOR_TEST = 209,
3105 #[doc = "Change to/from inverted flight."]
3106 MAV_CMD_DO_INVERTED_FLIGHT = 210,
3107 #[doc = "Mission command to operate a gripper."]
3108 MAV_CMD_DO_GRIPPER = 211,
3109 #[doc = "Enable/disable autotune."]
3110 MAV_CMD_DO_AUTOTUNE_ENABLE = 212,
3111 #[doc = "Sets a desired vehicle turn angle and speed change."]
3112 MAV_CMD_NAV_SET_YAW_SPEED = 213,
3113 #[doc = "Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera."]
3114 MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL = 214,
3115 #[doc = "Mission command to control a camera or antenna mount, using a quaternion as reference."]
3116 MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220,
3117 #[doc = "set id of master controller"]
3118 MAV_CMD_DO_GUIDED_MASTER = 221,
3119 #[doc = "Set limits for external control"]
3120 MAV_CMD_DO_GUIDED_LIMITS = 222,
3121 #[doc = "Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines"]
3122 MAV_CMD_DO_ENGINE_CONTROL = 223,
3123 #[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. \t Note that mission jump repeat counters are not reset unless param2 is set (see MAV_CMD_DO_JUMP param2). This command may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this command must not trigger a switch to mission mode. The mission may be \"reset\" using param2. Resetting sets jump counters to initial values (to reset counters without changing the current mission item set the param1 to `-1`). Resetting also explicitly changes a mission state of MISSION_STATE_COMPLETE to MISSION_STATE_PAUSED or MISSION_STATE_ACTIVE, potentially allowing it to resume when it is (next) in a mission mode. \t The command will ACK with MAV_RESULT_FAILED if the sequence number is out of range (including if there is no mission item)."]
3124 MAV_CMD_DO_SET_MISSION_CURRENT = 224,
3125 #[doc = "NOP - This command is only used to mark the upper limit of the DO commands in the enumeration"]
3126 MAV_CMD_DO_LAST = 240,
3127 #[doc = "Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero."]
3128 MAV_CMD_PREFLIGHT_CALIBRATION = 241,
3129 #[doc = "Set sensor offsets. This command will be only accepted if in pre-flight mode."]
3130 MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242,
3131 #[doc = "Trigger UAVCAN configuration (actuator ID assignment and direction mapping). Note that this maps to the legacy UAVCAN v0 function UAVCAN_ENUMERATE, which is intended to be executed just once during initial vehicle configuration (it is not a normal pre-flight command and has been poorly named)."]
3132 MAV_CMD_PREFLIGHT_UAVCAN = 243,
3133 #[doc = "Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode."]
3134 MAV_CMD_PREFLIGHT_STORAGE = 245,
3135 #[doc = "Request the reboot or shutdown of system components."]
3136 MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246,
3137 #[doc = "Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position."]
3138 MAV_CMD_OVERRIDE_GOTO = 252,
3139 #[doc = "Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera."]
3140 MAV_CMD_OBLIQUE_SURVEY = 260,
3141 #[doc = "Enable the specified standard MAVLink mode. If the specified mode is not supported, the vehicle should ACK with MAV_RESULT_FAILED. See <https://mavlink.io/en/services/standard_modes.html>"]
3142 MAV_CMD_DO_SET_STANDARD_MODE = 262,
3143 #[doc = "start running a mission"]
3144 MAV_CMD_MISSION_START = 300,
3145 #[doc = "Actuator testing command. This is similar to MAV_CMD_DO_MOTOR_TEST but operates on the level of output functions, i.e. it is possible to test Motor1 independent from which output it is configured on. Autopilots must NACK this command with MAV_RESULT_TEMPORARILY_REJECTED while armed."]
3146 MAV_CMD_ACTUATOR_TEST = 310,
3147 #[doc = "Actuator configuration command."]
3148 MAV_CMD_CONFIGURE_ACTUATOR = 311,
3149 #[doc = "Arms / Disarms a component"]
3150 MAV_CMD_COMPONENT_ARM_DISARM = 400,
3151 #[doc = "Instructs a target system to run pre-arm checks. This allows preflight checks to be run on demand, which may be useful on systems that normally run them at low rate, or which do not trigger checks when the armable state might have changed. This command should return MAV_RESULT_ACCEPTED if it will run the checks. The results of the checks are usually then reported in SYS_STATUS messages (this is system-specific). The command should return MAV_RESULT_TEMPORARILY_REJECTED if the system is already armed."]
3152 MAV_CMD_RUN_PREARM_CHECKS = 401,
3153 #[doc = "Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
3154 MAV_CMD_ILLUMINATOR_ON_OFF = 405,
3155 #[doc = "Configures illuminator settings. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
3156 MAV_CMD_DO_ILLUMINATOR_CONFIGURE = 406,
3157 #[doc = "Request the home position from the vehicle. \t The vehicle will ACK the command and then emit the HOME_POSITION message."]
3158 MAV_CMD_GET_HOME_POSITION = 410,
3159 #[doc = "Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting."]
3160 MAV_CMD_INJECT_FAILURE = 420,
3161 #[doc = "Starts receiver pairing."]
3162 MAV_CMD_START_RX_PAIR = 500,
3163 #[doc = "Request the interval between messages for a particular MAVLink message ID. The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message."]
3164 MAV_CMD_GET_MESSAGE_INTERVAL = 510,
3165 #[doc = "Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM."]
3166 MAV_CMD_SET_MESSAGE_INTERVAL = 511,
3167 #[doc = "Request the target system(s) emit a single instance of a specified message (i.e. a \"one-shot\" version of MAV_CMD_SET_MESSAGE_INTERVAL)."]
3168 MAV_CMD_REQUEST_MESSAGE = 512,
3169 #[doc = "Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message"]
3170 MAV_CMD_REQUEST_PROTOCOL_VERSION = 519,
3171 #[doc = "Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message"]
3172 MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520,
3173 #[doc = "Request camera information (CAMERA_INFORMATION)."]
3174 MAV_CMD_REQUEST_CAMERA_INFORMATION = 521,
3175 #[doc = "Request camera settings (CAMERA_SETTINGS)."]
3176 MAV_CMD_REQUEST_CAMERA_SETTINGS = 522,
3177 #[doc = "Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage."]
3178 MAV_CMD_REQUEST_STORAGE_INFORMATION = 525,
3179 #[doc = "Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage."]
3180 MAV_CMD_STORAGE_FORMAT = 526,
3181 #[doc = "Request camera capture status (CAMERA_CAPTURE_STATUS)"]
3182 MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS = 527,
3183 #[doc = "Request flight information (FLIGHT_INFORMATION)"]
3184 MAV_CMD_REQUEST_FLIGHT_INFORMATION = 528,
3185 #[doc = "Reset all camera settings to Factory Default"]
3186 MAV_CMD_RESET_CAMERA_SETTINGS = 529,
3187 #[doc = "Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming."]
3188 MAV_CMD_SET_CAMERA_MODE = 530,
3189 #[doc = "Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success)."]
3190 MAV_CMD_SET_CAMERA_ZOOM = 531,
3191 #[doc = "Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success)."]
3192 MAV_CMD_SET_CAMERA_FOCUS = 532,
3193 #[doc = "Set that a particular storage is the preferred location for saving photos, videos, and/or other media (e.g. to set that an SD card is used for storing videos). There can only be one preferred save location for each particular media type: setting a media usage flag will clear/reset that same flag if set on any other storage. If no flag is set the system should use its default storage. A target system can choose to always use default storage, in which case it should ACK the command with MAV_RESULT_UNSUPPORTED. A target system can choose to not allow a particular storage to be set as preferred storage, in which case it should ACK the command with MAV_RESULT_DENIED."]
3194 MAV_CMD_SET_STORAGE_USAGE = 533,
3195 #[doc = "Set camera source. Changes the camera's active sources on cameras with multiple image sensors."]
3196 MAV_CMD_SET_CAMERA_SOURCE = 534,
3197 #[doc = "Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG."]
3198 MAV_CMD_JUMP_TAG = 600,
3199 #[doc = "Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number."]
3200 MAV_CMD_DO_JUMP_TAG = 601,
3201 #[doc = "Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate."]
3202 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000,
3203 #[doc = "Gimbal configuration to set which sysid/compid is in primary and secondary control."]
3204 MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001,
3205 #[doc = "Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param 1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels."]
3206 MAV_CMD_IMAGE_START_CAPTURE = 2000,
3207 #[doc = "Stop image capture sequence. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels."]
3208 MAV_CMD_IMAGE_STOP_CAPTURE = 2001,
3209 #[doc = "Re-request a CAMERA_IMAGE_CAPTURED message."]
3210 MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE = 2002,
3211 #[doc = "Enable or disable on-board camera triggering system."]
3212 MAV_CMD_DO_TRIGGER_CONTROL = 2003,
3213 #[doc = "If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking."]
3214 MAV_CMD_CAMERA_TRACK_POINT = 2004,
3215 #[doc = "If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking."]
3216 MAV_CMD_CAMERA_TRACK_RECTANGLE = 2005,
3217 #[doc = "Stops ongoing tracking."]
3218 MAV_CMD_CAMERA_STOP_TRACKING = 2010,
3219 #[doc = "Starts video capture (recording)."]
3220 MAV_CMD_VIDEO_START_CAPTURE = 2500,
3221 #[doc = "Stop the current video capture (recording)."]
3222 MAV_CMD_VIDEO_STOP_CAPTURE = 2501,
3223 #[doc = "Start video streaming"]
3224 MAV_CMD_VIDEO_START_STREAMING = 2502,
3225 #[doc = "Stop the given video stream"]
3226 MAV_CMD_VIDEO_STOP_STREAMING = 2503,
3227 #[doc = "Request video stream information (VIDEO_STREAM_INFORMATION)"]
3228 MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION = 2504,
3229 #[doc = "Request video stream status (VIDEO_STREAM_STATUS)"]
3230 MAV_CMD_REQUEST_VIDEO_STREAM_STATUS = 2505,
3231 #[doc = "Request to start streaming logging data over MAVLink (see also LOGGING_DATA message)"]
3232 MAV_CMD_LOGGING_START = 2510,
3233 #[doc = "Request to stop streaming log data over MAVLink"]
3234 MAV_CMD_LOGGING_STOP = 2511,
3235 MAV_CMD_AIRFRAME_CONFIGURATION = 2520,
3236 #[doc = "Request to start/stop transmitting over the high latency telemetry"]
3237 MAV_CMD_CONTROL_HIGH_LATENCY = 2600,
3238 #[doc = "Create a panorama at the current position"]
3239 MAV_CMD_PANORAMA_CREATE = 2800,
3240 #[doc = "Request VTOL transition"]
3241 MAV_CMD_DO_VTOL_TRANSITION = 3000,
3242 #[doc = "Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. \t\tIf approved the COMMAND_ACK message progress field should be set with period of time that this authorization is valid in seconds. \t\tIf the authorization is denied COMMAND_ACK.result_param2 should be set with one of the reasons in ARM_AUTH_DENIED_REASON."]
3243 MAV_CMD_ARM_AUTHORIZATION_REQUEST = 3001,
3244 #[doc = "This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes."]
3245 MAV_CMD_SET_GUIDED_SUBMODE_STANDARD = 4000,
3246 #[doc = "This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position."]
3247 MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE = 4001,
3248 #[doc = "Delay mission state machine until gate has been reached."]
3249 MAV_CMD_CONDITION_GATE = 4501,
3250 #[doc = "Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead."]
3251 MAV_CMD_NAV_FENCE_RETURN_POINT = 5000,
3252 #[doc = "Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required. The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon."]
3253 MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION = 5001,
3254 #[doc = "Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required. The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon."]
3255 MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION = 5002,
3256 #[doc = "Circular fence area. The vehicle must stay inside this area."]
3257 MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION = 5003,
3258 #[doc = "Circular fence area. The vehicle must stay outside this area."]
3259 MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION = 5004,
3260 #[doc = "Rally point. You can have multiple rally points defined."]
3261 MAV_CMD_NAV_RALLY_POINT = 5100,
3262 #[doc = "Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages."]
3263 MAV_CMD_UAVCAN_GET_NODE_INFO = 5200,
3264 #[doc = "Change state of safety switch."]
3265 MAV_CMD_DO_SET_SAFETY_SWITCH_STATE = 5300,
3266 #[doc = "Trigger the start of an ADSB-out IDENT. This should only be used when requested to do so by an Air Traffic Controller in controlled airspace. This starts the IDENT which is then typically held for 18 seconds by the hardware per the Mode A, C, and S transponder spec."]
3267 MAV_CMD_DO_ADSB_OUT_IDENT = 10001,
3268 #[doc = "Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity."]
3269 MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001,
3270 #[doc = "Control the payload deployment."]
3271 MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002,
3272 #[doc = "Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location."]
3273 MAV_CMD_FIXED_MAG_CAL_YAW = 42006,
3274 #[doc = "Command to operate winch."]
3275 MAV_CMD_DO_WINCH = 42600,
3276 #[doc = "Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link."]
3277 MAV_CMD_EXTERNAL_POSITION_ESTIMATE = 43003,
3278 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3279 MAV_CMD_WAYPOINT_USER_1 = 31000,
3280 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3281 MAV_CMD_WAYPOINT_USER_2 = 31001,
3282 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3283 MAV_CMD_WAYPOINT_USER_3 = 31002,
3284 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3285 MAV_CMD_WAYPOINT_USER_4 = 31003,
3286 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3287 MAV_CMD_WAYPOINT_USER_5 = 31004,
3288 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3289 MAV_CMD_SPATIAL_USER_1 = 31005,
3290 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3291 MAV_CMD_SPATIAL_USER_2 = 31006,
3292 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3293 MAV_CMD_SPATIAL_USER_3 = 31007,
3294 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3295 MAV_CMD_SPATIAL_USER_4 = 31008,
3296 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3297 MAV_CMD_SPATIAL_USER_5 = 31009,
3298 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3299 MAV_CMD_USER_1 = 31010,
3300 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3301 MAV_CMD_USER_2 = 31011,
3302 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3303 MAV_CMD_USER_3 = 31012,
3304 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3305 MAV_CMD_USER_4 = 31013,
3306 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3307 MAV_CMD_USER_5 = 31014,
3308 #[doc = "Request forwarding of CAN packets from the given CAN bus to this component. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages"]
3309 MAV_CMD_CAN_FORWARD = 32000,
3310}
3311impl MavCmd {
3312 pub const DEFAULT: Self = Self::MAV_CMD_NAV_WAYPOINT;
3313}
3314impl Default for MavCmd {
3315 fn default() -> Self {
3316 Self::DEFAULT
3317 }
3318}
3319#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3320#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3321#[cfg_attr(feature = "serde", serde(tag = "type"))]
3322#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3323#[repr(u32)]
3324#[doc = "Flags to indicate the status of camera storage."]
3325pub enum StorageStatus {
3326 #[doc = "Storage is missing (no microSD card loaded for example.)"]
3327 STORAGE_STATUS_EMPTY = 0,
3328 #[doc = "Storage present but unformatted."]
3329 STORAGE_STATUS_UNFORMATTED = 1,
3330 #[doc = "Storage present and ready."]
3331 STORAGE_STATUS_READY = 2,
3332 #[doc = "Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored."]
3333 STORAGE_STATUS_NOT_SUPPORTED = 3,
3334}
3335impl StorageStatus {
3336 pub const DEFAULT: Self = Self::STORAGE_STATUS_EMPTY;
3337}
3338impl Default for StorageStatus {
3339 fn default() -> Self {
3340 Self::DEFAULT
3341 }
3342}
3343bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for ADS-B transponder dynamic report"] pub struct UavionixAdsbOutDynamicState : u16 { const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE = 1 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED = 2 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED = 4 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND = 8 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT = 16 ; } }
3344impl UavionixAdsbOutDynamicState {
3345 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE;
3346}
3347impl Default for UavionixAdsbOutDynamicState {
3348 fn default() -> Self {
3349 Self::DEFAULT
3350 }
3351}
3352#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3353#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3354#[cfg_attr(feature = "serde", serde(tag = "type"))]
3355#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3356#[repr(u32)]
3357#[doc = "Status for ADS-B transponder dynamic input"]
3358pub enum UavionixAdsbOutDynamicGpsFix {
3359 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_0 = 0,
3360 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_1 = 1,
3361 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_2D = 2,
3362 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_3D = 3,
3363 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_DGPS = 4,
3364 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_RTK = 5,
3365}
3366impl UavionixAdsbOutDynamicGpsFix {
3367 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_0;
3368}
3369impl Default for UavionixAdsbOutDynamicGpsFix {
3370 fn default() -> Self {
3371 Self::DEFAULT
3372 }
3373}
3374#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3375#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3376#[cfg_attr(feature = "serde", serde(tag = "type"))]
3377#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3378#[repr(u32)]
3379#[doc = "Definitions for aircraft size"]
3380pub enum UavionixAdsbOutCfgAircraftSize {
3381 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_NO_DATA = 0,
3382 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L15M_W23M = 1,
3383 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25M_W28P5M = 2,
3384 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25_34M = 3,
3385 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_33M = 4,
3386 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_38M = 5,
3387 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_39P5M = 6,
3388 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_45M = 7,
3389 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_45M = 8,
3390 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_52M = 9,
3391 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_59P5M = 10,
3392 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_67M = 11,
3393 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W72P5M = 12,
3394 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W80M = 13,
3395 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W80M = 14,
3396 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W90M = 15,
3397}
3398impl UavionixAdsbOutCfgAircraftSize {
3399 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_NO_DATA;
3400}
3401impl Default for UavionixAdsbOutCfgAircraftSize {
3402 fn default() -> Self {
3403 Self::DEFAULT
3404 }
3405}
3406bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates that none of the setpoint dimensions should be ignored."] pub struct AttitudeTargetTypemask : u8 { # [doc = "Ignore body roll rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE = 1 ; # [doc = "Ignore body pitch rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE = 2 ; # [doc = "Ignore body yaw rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE = 4 ; # [doc = "Use 3D body thrust setpoint instead of throttle"] const ATTITUDE_TARGET_TYPEMASK_THRUST_BODY_SET = 32 ; # [doc = "Ignore throttle"] const ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE = 64 ; # [doc = "Ignore attitude"] const ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE = 128 ; } }
3407impl AttitudeTargetTypemask {
3408 pub const DEFAULT: Self = Self::ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE;
3409}
3410impl Default for AttitudeTargetTypemask {
3411 fn default() -> Self {
3412 Self::DEFAULT
3413 }
3414}
3415#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3416#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3417#[cfg_attr(feature = "serde", serde(tag = "type"))]
3418#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3419#[repr(u32)]
3420#[doc = "RC sub-type of types defined in RC_TYPE. Used in MAV_CMD_START_RX_PAIR. Ignored if value does not correspond to the set RC_TYPE."]
3421pub enum RcSubType {
3422 #[doc = "Spektrum DSM2"]
3423 RC_SUB_TYPE_SPEKTRUM_DSM2 = 0,
3424 #[doc = "Spektrum DSMX"]
3425 RC_SUB_TYPE_SPEKTRUM_DSMX = 1,
3426 #[doc = "Spektrum DSMX8"]
3427 RC_SUB_TYPE_SPEKTRUM_DSMX8 = 2,
3428}
3429impl RcSubType {
3430 pub const DEFAULT: Self = Self::RC_SUB_TYPE_SPEKTRUM_DSM2;
3431}
3432impl Default for RcSubType {
3433 fn default() -> Self {
3434 Self::DEFAULT
3435 }
3436}
3437#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3438#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3439#[cfg_attr(feature = "serde", serde(tag = "type"))]
3440#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3441#[repr(u32)]
3442#[doc = "List of possible failure type to inject."]
3443pub enum FailureType {
3444 #[doc = "No failure injected, used to reset a previous failure."]
3445 FAILURE_TYPE_OK = 0,
3446 #[doc = "Sets unit off, so completely non-responsive."]
3447 FAILURE_TYPE_OFF = 1,
3448 #[doc = "Unit is stuck e.g. keeps reporting the same value."]
3449 FAILURE_TYPE_STUCK = 2,
3450 #[doc = "Unit is reporting complete garbage."]
3451 FAILURE_TYPE_GARBAGE = 3,
3452 #[doc = "Unit is consistently wrong."]
3453 FAILURE_TYPE_WRONG = 4,
3454 #[doc = "Unit is slow, so e.g. reporting at slower than expected rate."]
3455 FAILURE_TYPE_SLOW = 5,
3456 #[doc = "Data of unit is delayed in time."]
3457 FAILURE_TYPE_DELAYED = 6,
3458 #[doc = "Unit is sometimes working, sometimes not."]
3459 FAILURE_TYPE_INTERMITTENT = 7,
3460}
3461impl FailureType {
3462 pub const DEFAULT: Self = Self::FAILURE_TYPE_OK;
3463}
3464impl Default for FailureType {
3465 fn default() -> Self {
3466 Self::DEFAULT
3467 }
3468}
3469#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3470#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3471#[cfg_attr(feature = "serde", serde(tag = "type"))]
3472#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3473#[repr(u32)]
3474pub enum MavOdidCategoryEu {
3475 #[doc = "The category for the UA, according to the EU specification, is undeclared."]
3476 MAV_ODID_CATEGORY_EU_UNDECLARED = 0,
3477 #[doc = "The category for the UA, according to the EU specification, is the Open category."]
3478 MAV_ODID_CATEGORY_EU_OPEN = 1,
3479 #[doc = "The category for the UA, according to the EU specification, is the Specific category."]
3480 MAV_ODID_CATEGORY_EU_SPECIFIC = 2,
3481 #[doc = "The category for the UA, according to the EU specification, is the Certified category."]
3482 MAV_ODID_CATEGORY_EU_CERTIFIED = 3,
3483}
3484impl MavOdidCategoryEu {
3485 pub const DEFAULT: Self = Self::MAV_ODID_CATEGORY_EU_UNDECLARED;
3486}
3487impl Default for MavOdidCategoryEu {
3488 fn default() -> Self {
3489 Self::DEFAULT
3490 }
3491}
3492#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3493#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3494#[cfg_attr(feature = "serde", serde(tag = "type"))]
3495#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3496#[repr(u32)]
3497pub enum MavOdidSpeedAcc {
3498 #[doc = "The speed accuracy is unknown."]
3499 MAV_ODID_SPEED_ACC_UNKNOWN = 0,
3500 #[doc = "The speed accuracy is smaller than 10 meters per second."]
3501 MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND = 1,
3502 #[doc = "The speed accuracy is smaller than 3 meters per second."]
3503 MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND = 2,
3504 #[doc = "The speed accuracy is smaller than 1 meters per second."]
3505 MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND = 3,
3506 #[doc = "The speed accuracy is smaller than 0.3 meters per second."]
3507 MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND = 4,
3508}
3509impl MavOdidSpeedAcc {
3510 pub const DEFAULT: Self = Self::MAV_ODID_SPEED_ACC_UNKNOWN;
3511}
3512impl Default for MavOdidSpeedAcc {
3513 fn default() -> Self {
3514 Self::DEFAULT
3515 }
3516}
3517#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3518#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3519#[cfg_attr(feature = "serde", serde(tag = "type"))]
3520#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3521#[repr(u32)]
3522#[doc = "Emergency status encoding"]
3523pub enum UavionixAdsbEmergencyStatus {
3524 UAVIONIX_ADSB_OUT_NO_EMERGENCY = 0,
3525 UAVIONIX_ADSB_OUT_GENERAL_EMERGENCY = 1,
3526 UAVIONIX_ADSB_OUT_LIFEGUARD_EMERGENCY = 2,
3527 UAVIONIX_ADSB_OUT_MINIMUM_FUEL_EMERGENCY = 3,
3528 UAVIONIX_ADSB_OUT_NO_COMM_EMERGENCY = 4,
3529 UAVIONIX_ADSB_OUT_UNLAWFUL_INTERFERANCE_EMERGENCY = 5,
3530 UAVIONIX_ADSB_OUT_DOWNED_AIRCRAFT_EMERGENCY = 6,
3531 UAVIONIX_ADSB_OUT_RESERVED = 7,
3532}
3533impl UavionixAdsbEmergencyStatus {
3534 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_NO_EMERGENCY;
3535}
3536impl Default for UavionixAdsbEmergencyStatus {
3537 fn default() -> Self {
3538 Self::DEFAULT
3539 }
3540}
3541#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3542#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3543#[cfg_attr(feature = "serde", serde(tag = "type"))]
3544#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3545#[repr(u32)]
3546#[doc = "Possible actions an aircraft can take to avoid a collision."]
3547pub enum MavCollisionAction {
3548 #[doc = "Ignore any potential collisions"]
3549 MAV_COLLISION_ACTION_NONE = 0,
3550 #[doc = "Report potential collision"]
3551 MAV_COLLISION_ACTION_REPORT = 1,
3552 #[doc = "Ascend or Descend to avoid threat"]
3553 MAV_COLLISION_ACTION_ASCEND_OR_DESCEND = 2,
3554 #[doc = "Move horizontally to avoid threat"]
3555 MAV_COLLISION_ACTION_MOVE_HORIZONTALLY = 3,
3556 #[doc = "Aircraft to move perpendicular to the collision's velocity vector"]
3557 MAV_COLLISION_ACTION_MOVE_PERPENDICULAR = 4,
3558 #[doc = "Aircraft to fly directly back to its launch point"]
3559 MAV_COLLISION_ACTION_RTL = 5,
3560 #[doc = "Aircraft to stop in place"]
3561 MAV_COLLISION_ACTION_HOVER = 6,
3562}
3563impl MavCollisionAction {
3564 pub const DEFAULT: Self = Self::MAV_COLLISION_ACTION_NONE;
3565}
3566impl Default for MavCollisionAction {
3567 fn default() -> Self {
3568 Self::DEFAULT
3569 }
3570}
3571#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3572#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3573#[cfg_attr(feature = "serde", serde(tag = "type"))]
3574#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3575#[repr(u32)]
3576#[doc = "Enumeration of distance sensor types"]
3577pub enum MavDistanceSensor {
3578 #[doc = "Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units"]
3579 MAV_DISTANCE_SENSOR_LASER = 0,
3580 #[doc = "Ultrasound rangefinder, e.g. MaxBotix units"]
3581 MAV_DISTANCE_SENSOR_ULTRASOUND = 1,
3582 #[doc = "Infrared rangefinder, e.g. Sharp units"]
3583 MAV_DISTANCE_SENSOR_INFRARED = 2,
3584 #[doc = "Radar type, e.g. uLanding units"]
3585 MAV_DISTANCE_SENSOR_RADAR = 3,
3586 #[doc = "Broken or unknown type, e.g. analog units"]
3587 MAV_DISTANCE_SENSOR_UNKNOWN = 4,
3588}
3589impl MavDistanceSensor {
3590 pub const DEFAULT: Self = Self::MAV_DISTANCE_SENSOR_LASER;
3591}
3592impl Default for MavDistanceSensor {
3593 fn default() -> Self {
3594 Self::DEFAULT
3595 }
3596}
3597#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3598#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3599#[cfg_attr(feature = "serde", serde(tag = "type"))]
3600#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3601#[repr(u32)]
3602#[doc = "Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: <http://www.kiwisyslog.com/kb/info:-syslog-message-levels/>."]
3603pub enum MavSeverity {
3604 #[doc = "System is unusable. This is a \"panic\" condition."]
3605 MAV_SEVERITY_EMERGENCY = 0,
3606 #[doc = "Action should be taken immediately. Indicates error in non-critical systems."]
3607 MAV_SEVERITY_ALERT = 1,
3608 #[doc = "Action must be taken immediately. Indicates failure in a primary system."]
3609 MAV_SEVERITY_CRITICAL = 2,
3610 #[doc = "Indicates an error in secondary/redundant systems."]
3611 MAV_SEVERITY_ERROR = 3,
3612 #[doc = "Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning."]
3613 MAV_SEVERITY_WARNING = 4,
3614 #[doc = "An unusual event has occurred, though not an error condition. This should be investigated for the root cause."]
3615 MAV_SEVERITY_NOTICE = 5,
3616 #[doc = "Normal operational messages. Useful for logging. No action is required for these messages."]
3617 MAV_SEVERITY_INFO = 6,
3618 #[doc = "Useful non-operational messages that can assist in debugging. These should not occur during normal operation."]
3619 MAV_SEVERITY_DEBUG = 7,
3620}
3621impl MavSeverity {
3622 pub const DEFAULT: Self = Self::MAV_SEVERITY_EMERGENCY;
3623}
3624impl Default for MavSeverity {
3625 fn default() -> Self {
3626 Self::DEFAULT
3627 }
3628}
3629bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for ADS-B transponder dynamic report"] pub struct UavionixAdsbOutControlState : u8 { const UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED = 1 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND = 4 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE = 8 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED = 16 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED = 32 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED = 64 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED = 128 ; } }
3630impl UavionixAdsbOutControlState {
3631 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED;
3632}
3633impl Default for UavionixAdsbOutControlState {
3634 fn default() -> Self {
3635 Self::DEFAULT
3636 }
3637}
3638bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for X-Bit and reserved fields."] pub struct UavionixAdsbXbit : u8 { const UAVIONIX_ADSB_XBIT_ENABLED = 128 ; } }
3639impl UavionixAdsbXbit {
3640 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_XBIT_ENABLED;
3641}
3642impl Default for UavionixAdsbXbit {
3643 fn default() -> Self {
3644 Self::DEFAULT
3645 }
3646}
3647#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3648#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3649#[cfg_attr(feature = "serde", serde(tag = "type"))]
3650#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3651#[repr(u32)]
3652#[doc = "RTK GPS baseline coordinate system, used for RTK corrections"]
3653pub enum RtkBaselineCoordinateSystem {
3654 #[doc = "Earth-centered, Earth-fixed"]
3655 RTK_BASELINE_COORDINATE_SYSTEM_ECEF = 0,
3656 #[doc = "RTK basestation centered, north, east, down"]
3657 RTK_BASELINE_COORDINATE_SYSTEM_NED = 1,
3658}
3659impl RtkBaselineCoordinateSystem {
3660 pub const DEFAULT: Self = Self::RTK_BASELINE_COORDINATE_SYSTEM_ECEF;
3661}
3662impl Default for RtkBaselineCoordinateSystem {
3663 fn default() -> Self {
3664 Self::DEFAULT
3665 }
3666}
3667#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3668#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3669#[cfg_attr(feature = "serde", serde(tag = "type"))]
3670#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3671#[repr(u32)]
3672#[doc = "Possible safety switch states."]
3673pub enum SafetySwitchState {
3674 #[doc = "Safety switch is engaged and vehicle should be safe to approach."]
3675 SAFETY_SWITCH_STATE_SAFE = 0,
3676 #[doc = "Safety switch is NOT engaged and motors, propellers and other actuators should be considered active."]
3677 SAFETY_SWITCH_STATE_DANGEROUS = 1,
3678}
3679impl SafetySwitchState {
3680 pub const DEFAULT: Self = Self::SAFETY_SWITCH_STATE_SAFE;
3681}
3682impl Default for SafetySwitchState {
3683 fn default() -> Self {
3684 Self::DEFAULT
3685 }
3686}
3687bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Illuminator module error flags (bitmap, 0 means no error)"] pub struct IlluminatorErrorFlags : u32 { # [doc = "Illuminator thermal throttling error."] const ILLUMINATOR_ERROR_FLAGS_THERMAL_THROTTLING = 1 ; # [doc = "Illuminator over temperature shutdown error."] const ILLUMINATOR_ERROR_FLAGS_OVER_TEMPERATURE_SHUTDOWN = 2 ; # [doc = "Illuminator thermistor failure."] const ILLUMINATOR_ERROR_FLAGS_THERMISTOR_FAILURE = 4 ; } }
3688impl IlluminatorErrorFlags {
3689 pub const DEFAULT: Self = Self::ILLUMINATOR_ERROR_FLAGS_THERMAL_THROTTLING;
3690}
3691impl Default for IlluminatorErrorFlags {
3692 fn default() -> Self {
3693 Self::DEFAULT
3694 }
3695}
3696#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3697#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3698#[cfg_attr(feature = "serde", serde(tag = "type"))]
3699#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3700#[repr(u32)]
3701#[doc = "Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands."]
3702pub enum ActuatorConfiguration {
3703 #[doc = "Do nothing."]
3704 ACTUATOR_CONFIGURATION_NONE = 0,
3705 #[doc = "Command the actuator to beep now."]
3706 ACTUATOR_CONFIGURATION_BEEP = 1,
3707 #[doc = "Permanently set the actuator (ESC) to 3D mode (reversible thrust)."]
3708 ACTUATOR_CONFIGURATION_3D_MODE_ON = 2,
3709 #[doc = "Permanently set the actuator (ESC) to non 3D mode (non-reversible thrust)."]
3710 ACTUATOR_CONFIGURATION_3D_MODE_OFF = 3,
3711 #[doc = "Permanently set the actuator (ESC) to spin direction 1 (which can be clockwise or counter-clockwise)."]
3712 ACTUATOR_CONFIGURATION_SPIN_DIRECTION1 = 4,
3713 #[doc = "Permanently set the actuator (ESC) to spin direction 2 (opposite of direction 1)."]
3714 ACTUATOR_CONFIGURATION_SPIN_DIRECTION2 = 5,
3715}
3716impl ActuatorConfiguration {
3717 pub const DEFAULT: Self = Self::ACTUATOR_CONFIGURATION_NONE;
3718}
3719impl Default for ActuatorConfiguration {
3720 fn default() -> Self {
3721 Self::DEFAULT
3722 }
3723}
3724#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3725#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3726#[cfg_attr(feature = "serde", serde(tag = "type"))]
3727#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3728#[repr(u32)]
3729#[doc = "MAV FTP error codes (<https://mavlink.io/en/services/ftp.html>)"]
3730pub enum MavFtpErr {
3731 #[doc = "None: No error"]
3732 MAV_FTP_ERR_NONE = 0,
3733 #[doc = "Fail: Unknown failure"]
3734 MAV_FTP_ERR_FAIL = 1,
3735 #[doc = "FailErrno: Command failed, Err number sent back in PayloadHeader.data[1]. \t\tThis is a file-system error number understood by the server operating system."]
3736 MAV_FTP_ERR_FAILERRNO = 2,
3737 #[doc = "InvalidDataSize: Payload size is invalid"]
3738 MAV_FTP_ERR_INVALIDDATASIZE = 3,
3739 #[doc = "InvalidSession: Session is not currently open"]
3740 MAV_FTP_ERR_INVALIDSESSION = 4,
3741 #[doc = "NoSessionsAvailable: All available sessions are already in use"]
3742 MAV_FTP_ERR_NOSESSIONSAVAILABLE = 5,
3743 #[doc = "EOF: Offset past end of file for ListDirectory and ReadFile commands"]
3744 MAV_FTP_ERR_EOF = 6,
3745 #[doc = "UnknownCommand: Unknown command / opcode"]
3746 MAV_FTP_ERR_UNKNOWNCOMMAND = 7,
3747 #[doc = "FileExists: File/directory already exists"]
3748 MAV_FTP_ERR_FILEEXISTS = 8,
3749 #[doc = "FileProtected: File/directory is write protected"]
3750 MAV_FTP_ERR_FILEPROTECTED = 9,
3751 #[doc = "FileNotFound: File/directory not found"]
3752 MAV_FTP_ERR_FILENOTFOUND = 10,
3753}
3754impl MavFtpErr {
3755 pub const DEFAULT: Self = Self::MAV_FTP_ERR_NONE;
3756}
3757impl Default for MavFtpErr {
3758 fn default() -> Self {
3759 Self::DEFAULT
3760 }
3761}
3762#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3763#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3764#[cfg_attr(feature = "serde", serde(tag = "type"))]
3765#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3766#[repr(u32)]
3767#[doc = "Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution."]
3768pub enum MavGoto {
3769 #[doc = "Hold at the current position."]
3770 MAV_GOTO_DO_HOLD = 0,
3771 #[doc = "Continue with the next item in mission execution."]
3772 MAV_GOTO_DO_CONTINUE = 1,
3773 #[doc = "Hold at the current position of the system"]
3774 MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2,
3775 #[doc = "Hold at the position specified in the parameters of the DO_HOLD action"]
3776 MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3,
3777}
3778impl MavGoto {
3779 pub const DEFAULT: Self = Self::MAV_GOTO_DO_HOLD;
3780}
3781impl Default for MavGoto {
3782 fn default() -> Self {
3783 Self::DEFAULT
3784 }
3785}
3786bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for gimbal device (lower level) operation."] pub struct GimbalDeviceFlags : u16 { # [doc = "Set to retracted safe position (no stabilization), takes precedence over all other flags."] const GIMBAL_DEVICE_FLAGS_RETRACT = 1 ; # [doc = "Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation."] const GIMBAL_DEVICE_FLAGS_NEUTRAL = 2 ; # [doc = "Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal."] const GIMBAL_DEVICE_FLAGS_ROLL_LOCK = 4 ; # [doc = "Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal."] const GIMBAL_DEVICE_FLAGS_PITCH_LOCK = 8 ; # [doc = "Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward)."] const GIMBAL_DEVICE_FLAGS_YAW_LOCK = 16 ; # [doc = "Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward)."] const GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32 ; # [doc = "Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North)."] const GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64 ; # [doc = "Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored)."] const GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = 128 ; # [doc = "The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored."] const GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = 256 ; # [doc = "The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation."] const GIMBAL_DEVICE_FLAGS_RC_MIXED = 512 ; } }
3787impl GimbalDeviceFlags {
3788 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_FLAGS_RETRACT;
3789}
3790impl Default for GimbalDeviceFlags {
3791 fn default() -> Self {
3792 Self::DEFAULT
3793 }
3794}
3795bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid."] pub struct AisFlags : u16 { # [doc = "1 = Position accuracy less than 10m, 0 = position accuracy greater than 10m."] const AIS_FLAGS_POSITION_ACCURACY = 1 ; const AIS_FLAGS_VALID_COG = 2 ; const AIS_FLAGS_VALID_VELOCITY = 4 ; # [doc = "1 = Velocity over 52.5765m/s (102.2 knots)"] const AIS_FLAGS_HIGH_VELOCITY = 8 ; const AIS_FLAGS_VALID_TURN_RATE = 16 ; # [doc = "Only the sign of the returned turn rate value is valid, either greater than 5deg/30s or less than -5deg/30s"] const AIS_FLAGS_TURN_RATE_SIGN_ONLY = 32 ; const AIS_FLAGS_VALID_DIMENSIONS = 64 ; # [doc = "Distance to bow is larger than 511m"] const AIS_FLAGS_LARGE_BOW_DIMENSION = 128 ; # [doc = "Distance to stern is larger than 511m"] const AIS_FLAGS_LARGE_STERN_DIMENSION = 256 ; # [doc = "Distance to port side is larger than 63m"] const AIS_FLAGS_LARGE_PORT_DIMENSION = 512 ; # [doc = "Distance to starboard side is larger than 63m"] const AIS_FLAGS_LARGE_STARBOARD_DIMENSION = 1024 ; const AIS_FLAGS_VALID_CALLSIGN = 2048 ; const AIS_FLAGS_VALID_NAME = 4096 ; } }
3796impl AisFlags {
3797 pub const DEFAULT: Self = Self::AIS_FLAGS_POSITION_ACCURACY;
3798}
3799impl Default for AisFlags {
3800 fn default() -> Self {
3801 Self::DEFAULT
3802 }
3803}
3804#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3805#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3806#[cfg_attr(feature = "serde", serde(tag = "type"))]
3807#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3808#[repr(u32)]
3809#[doc = "These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not."]
3810pub enum MavModeFlagDecodePosition {
3811 #[doc = "First bit: 10000000"]
3812 MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128,
3813 #[doc = "Second bit: 01000000"]
3814 MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64,
3815 #[doc = "Third bit: 00100000"]
3816 MAV_MODE_FLAG_DECODE_POSITION_HIL = 32,
3817 #[doc = "Fourth bit: 00010000"]
3818 MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16,
3819 #[doc = "Fifth bit: 00001000"]
3820 MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8,
3821 #[doc = "Sixth bit: 00000100"]
3822 MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4,
3823 #[doc = "Seventh bit: 00000010"]
3824 MAV_MODE_FLAG_DECODE_POSITION_TEST = 2,
3825 #[doc = "Eighth bit: 00000001"]
3826 MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1,
3827}
3828impl MavModeFlagDecodePosition {
3829 pub const DEFAULT: Self = Self::MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
3830}
3831impl Default for MavModeFlagDecodePosition {
3832 fn default() -> Self {
3833 Self::DEFAULT
3834 }
3835}
3836#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3837#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3838#[cfg_attr(feature = "serde", serde(tag = "type"))]
3839#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3840#[repr(u32)]
3841#[doc = "Winch actions."]
3842pub enum WinchActions {
3843 #[doc = "Allow motor to freewheel."]
3844 WINCH_RELAXED = 0,
3845 #[doc = "Wind or unwind specified length of line, optionally using specified rate."]
3846 WINCH_RELATIVE_LENGTH_CONTROL = 1,
3847 #[doc = "Wind or unwind line at specified rate."]
3848 WINCH_RATE_CONTROL = 2,
3849 #[doc = "Perform the locking sequence to relieve motor while in the fully retracted position. Only action and instance command parameters are used, others are ignored."]
3850 WINCH_LOCK = 3,
3851 #[doc = "Sequence of drop, slow down, touch down, reel up, lock. Only action and instance command parameters are used, others are ignored."]
3852 WINCH_DELIVER = 4,
3853 #[doc = "Engage motor and hold current position. Only action and instance command parameters are used, others are ignored."]
3854 WINCH_HOLD = 5,
3855 #[doc = "Return the reel to the fully retracted position. Only action and instance command parameters are used, others are ignored."]
3856 WINCH_RETRACT = 6,
3857 #[doc = "Load the reel with line. The winch will calculate the total loaded length and stop when the tension exceeds a threshold. Only action and instance command parameters are used, others are ignored."]
3858 WINCH_LOAD_LINE = 7,
3859 #[doc = "Spool out the entire length of the line. Only action and instance command parameters are used, others are ignored."]
3860 WINCH_ABANDON_LINE = 8,
3861 #[doc = "Spools out just enough to present the hook to the user to load the payload. Only action and instance command parameters are used, others are ignored"]
3862 WINCH_LOAD_PAYLOAD = 9,
3863}
3864impl WinchActions {
3865 pub const DEFAULT: Self = Self::WINCH_RELAXED;
3866}
3867impl Default for WinchActions {
3868 fn default() -> Self {
3869 Self::DEFAULT
3870 }
3871}
3872bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS."] pub struct GimbalManagerFlags : u32 { # [doc = "Based on GIMBAL_DEVICE_FLAGS_RETRACT."] const GIMBAL_MANAGER_FLAGS_RETRACT = 1 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_NEUTRAL."] const GIMBAL_MANAGER_FLAGS_NEUTRAL = 2 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK."] const GIMBAL_MANAGER_FLAGS_ROLL_LOCK = 4 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK."] const GIMBAL_MANAGER_FLAGS_PITCH_LOCK = 8 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK."] const GIMBAL_MANAGER_FLAGS_YAW_LOCK = 16 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME."] const GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = 32 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = 64 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = 128 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE."] const GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = 256 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_RC_MIXED."] const GIMBAL_MANAGER_FLAGS_RC_MIXED = 512 ; } }
3873impl GimbalManagerFlags {
3874 pub const DEFAULT: Self = Self::GIMBAL_MANAGER_FLAGS_RETRACT;
3875}
3876impl Default for GimbalManagerFlags {
3877 fn default() -> Self {
3878 Self::DEFAULT
3879 }
3880}
3881#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3882#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3883#[cfg_attr(feature = "serde", serde(tag = "type"))]
3884#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3885#[repr(u32)]
3886#[doc = "Enumeration for battery charge states."]
3887pub enum MavBatteryChargeState {
3888 #[doc = "Low battery state is not provided"]
3889 MAV_BATTERY_CHARGE_STATE_UNDEFINED = 0,
3890 #[doc = "Battery is not in low state. Normal operation."]
3891 MAV_BATTERY_CHARGE_STATE_OK = 1,
3892 #[doc = "Battery state is low, warn and monitor close."]
3893 MAV_BATTERY_CHARGE_STATE_LOW = 2,
3894 #[doc = "Battery state is critical, return or abort immediately."]
3895 MAV_BATTERY_CHARGE_STATE_CRITICAL = 3,
3896 #[doc = "Battery state is too low for ordinary abort sequence. Perform fastest possible emergency stop to prevent damage."]
3897 MAV_BATTERY_CHARGE_STATE_EMERGENCY = 4,
3898 #[doc = "Battery failed, damage unavoidable. Possible causes (faults) are listed in MAV_BATTERY_FAULT."]
3899 MAV_BATTERY_CHARGE_STATE_FAILED = 5,
3900 #[doc = "Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in MAV_BATTERY_FAULT."]
3901 MAV_BATTERY_CHARGE_STATE_UNHEALTHY = 6,
3902 #[doc = "Battery is charging."]
3903 MAV_BATTERY_CHARGE_STATE_CHARGING = 7,
3904}
3905impl MavBatteryChargeState {
3906 pub const DEFAULT: Self = Self::MAV_BATTERY_CHARGE_STATE_UNDEFINED;
3907}
3908impl Default for MavBatteryChargeState {
3909 fn default() -> Self {
3910 Self::DEFAULT
3911 }
3912}
3913bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Camera tracking target data (shows where tracked target is within image)"] pub struct CameraTrackingTargetData : u8 { # [doc = "Target data embedded in image data (proprietary)"] const CAMERA_TRACKING_TARGET_DATA_EMBEDDED = 1 ; # [doc = "Target data rendered in image"] const CAMERA_TRACKING_TARGET_DATA_RENDERED = 2 ; # [doc = "Target data within status message (Point or Rectangle)"] const CAMERA_TRACKING_TARGET_DATA_IN_STATUS = 4 ; } }
3914impl CameraTrackingTargetData {
3915 pub const DEFAULT: Self = Self::CAMERA_TRACKING_TARGET_DATA_EMBEDDED;
3916}
3917impl Default for CameraTrackingTargetData {
3918 fn default() -> Self {
3919 Self::DEFAULT
3920 }
3921}
3922#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3923#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3924#[cfg_attr(feature = "serde", serde(tag = "type"))]
3925#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3926#[repr(u32)]
3927#[doc = "Indicates the ESC connection type."]
3928pub enum EscConnectionType {
3929 #[doc = "Traditional PPM ESC."]
3930 ESC_CONNECTION_TYPE_PPM = 0,
3931 #[doc = "Serial Bus connected ESC."]
3932 ESC_CONNECTION_TYPE_SERIAL = 1,
3933 #[doc = "One Shot PPM ESC."]
3934 ESC_CONNECTION_TYPE_ONESHOT = 2,
3935 #[doc = "I2C ESC."]
3936 ESC_CONNECTION_TYPE_I2C = 3,
3937 #[doc = "CAN-Bus ESC."]
3938 ESC_CONNECTION_TYPE_CAN = 4,
3939 #[doc = "DShot ESC."]
3940 ESC_CONNECTION_TYPE_DSHOT = 5,
3941}
3942impl EscConnectionType {
3943 pub const DEFAULT: Self = Self::ESC_CONNECTION_TYPE_PPM;
3944}
3945impl Default for EscConnectionType {
3946 fn default() -> Self {
3947 Self::DEFAULT
3948 }
3949}
3950#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3951#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3952#[cfg_attr(feature = "serde", serde(tag = "type"))]
3953#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3954#[repr(u32)]
3955#[doc = "States of the mission state machine. Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). They may not all be relevant on all vehicles."]
3956pub enum MissionState {
3957 #[doc = "The mission status reporting is not supported."]
3958 MISSION_STATE_UNKNOWN = 0,
3959 #[doc = "No mission on the vehicle."]
3960 MISSION_STATE_NO_MISSION = 1,
3961 #[doc = "Mission has not started. This is the case after a mission has uploaded but not yet started executing."]
3962 MISSION_STATE_NOT_STARTED = 2,
3963 #[doc = "Mission is active, and will execute mission items when in auto mode."]
3964 MISSION_STATE_ACTIVE = 3,
3965 #[doc = "Mission is paused when in auto mode."]
3966 MISSION_STATE_PAUSED = 4,
3967 #[doc = "Mission has executed all mission items."]
3968 MISSION_STATE_COMPLETE = 5,
3969}
3970impl MissionState {
3971 pub const DEFAULT: Self = Self::MISSION_STATE_UNKNOWN;
3972}
3973impl Default for MissionState {
3974 fn default() -> Self {
3975 Self::DEFAULT
3976 }
3977}
3978#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3979#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3980#[cfg_attr(feature = "serde", serde(tag = "type"))]
3981#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3982#[repr(u32)]
3983#[doc = "Battery mode. Note, the normal operation mode (i.e. when flying) should be reported as MAV_BATTERY_MODE_UNKNOWN to allow message trimming in normal flight."]
3984pub enum MavBatteryMode {
3985 #[doc = "Battery mode not supported/unknown battery mode/normal operation."]
3986 MAV_BATTERY_MODE_UNKNOWN = 0,
3987 #[doc = "Battery is auto discharging (towards storage level)."]
3988 MAV_BATTERY_MODE_AUTO_DISCHARGING = 1,
3989 #[doc = "Battery in hot-swap mode (current limited to prevent spikes that might damage sensitive electrical circuits)."]
3990 MAV_BATTERY_MODE_HOT_SWAP = 2,
3991}
3992impl MavBatteryMode {
3993 pub const DEFAULT: Self = Self::MAV_BATTERY_MODE_UNKNOWN;
3994}
3995impl Default for MavBatteryMode {
3996 fn default() -> Self {
3997 Self::DEFAULT
3998 }
3999}
4000#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4001#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4002#[cfg_attr(feature = "serde", serde(tag = "type"))]
4003#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4004#[repr(u32)]
4005#[doc = "WiFi Mode."]
4006pub enum WifiConfigApMode {
4007 #[doc = "WiFi mode is undefined."]
4008 WIFI_CONFIG_AP_MODE_UNDEFINED = 0,
4009 #[doc = "WiFi configured as an access point."]
4010 WIFI_CONFIG_AP_MODE_AP = 1,
4011 #[doc = "WiFi configured as a station connected to an existing local WiFi network."]
4012 WIFI_CONFIG_AP_MODE_STATION = 2,
4013 #[doc = "WiFi disabled."]
4014 WIFI_CONFIG_AP_MODE_DISABLED = 3,
4015}
4016impl WifiConfigApMode {
4017 pub const DEFAULT: Self = Self::WIFI_CONFIG_AP_MODE_UNDEFINED;
4018}
4019impl Default for WifiConfigApMode {
4020 fn default() -> Self {
4021 Self::DEFAULT
4022 }
4023}
4024#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4025#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4026#[cfg_attr(feature = "serde", serde(tag = "type"))]
4027#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4028#[repr(u32)]
4029#[doc = "Source of information about this collision."]
4030pub enum MavCollisionSrc {
4031 #[doc = "ID field references ADSB_VEHICLE packets"]
4032 MAV_COLLISION_SRC_ADSB = 0,
4033 #[doc = "ID field references MAVLink SRC ID"]
4034 MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT = 1,
4035}
4036impl MavCollisionSrc {
4037 pub const DEFAULT: Self = Self::MAV_COLLISION_SRC_ADSB;
4038}
4039impl Default for MavCollisionSrc {
4040 fn default() -> Self {
4041 Self::DEFAULT
4042 }
4043}
4044#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4045#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4046#[cfg_attr(feature = "serde", serde(tag = "type"))]
4047#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4048#[repr(u32)]
4049#[doc = "These flags encode the cellular network status"]
4050pub enum CellularStatusFlag {
4051 #[doc = "State unknown or not reportable."]
4052 CELLULAR_STATUS_FLAG_UNKNOWN = 0,
4053 #[doc = "Modem is unusable"]
4054 CELLULAR_STATUS_FLAG_FAILED = 1,
4055 #[doc = "Modem is being initialized"]
4056 CELLULAR_STATUS_FLAG_INITIALIZING = 2,
4057 #[doc = "Modem is locked"]
4058 CELLULAR_STATUS_FLAG_LOCKED = 3,
4059 #[doc = "Modem is not enabled and is powered down"]
4060 CELLULAR_STATUS_FLAG_DISABLED = 4,
4061 #[doc = "Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state"]
4062 CELLULAR_STATUS_FLAG_DISABLING = 5,
4063 #[doc = "Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state"]
4064 CELLULAR_STATUS_FLAG_ENABLING = 6,
4065 #[doc = "Modem is enabled and powered on but not registered with a network provider and not available for data connections"]
4066 CELLULAR_STATUS_FLAG_ENABLED = 7,
4067 #[doc = "Modem is searching for a network provider to register"]
4068 CELLULAR_STATUS_FLAG_SEARCHING = 8,
4069 #[doc = "Modem is registered with a network provider, and data connections and messaging may be available for use"]
4070 CELLULAR_STATUS_FLAG_REGISTERED = 9,
4071 #[doc = "Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated"]
4072 CELLULAR_STATUS_FLAG_DISCONNECTING = 10,
4073 #[doc = "Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered"]
4074 CELLULAR_STATUS_FLAG_CONNECTING = 11,
4075 #[doc = "One or more packet data bearers is active and connected"]
4076 CELLULAR_STATUS_FLAG_CONNECTED = 12,
4077}
4078impl CellularStatusFlag {
4079 pub const DEFAULT: Self = Self::CELLULAR_STATUS_FLAG_UNKNOWN;
4080}
4081impl Default for CellularStatusFlag {
4082 fn default() -> Self {
4083 Self::DEFAULT
4084 }
4085}
4086bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Power supply status flags (bitmask)"] pub struct MavPowerStatus : u16 { # [doc = "main brick power supply valid"] const MAV_POWER_STATUS_BRICK_VALID = 1 ; # [doc = "main servo power supply valid for FMU"] const MAV_POWER_STATUS_SERVO_VALID = 2 ; # [doc = "USB power is connected"] const MAV_POWER_STATUS_USB_CONNECTED = 4 ; # [doc = "peripheral supply is in over-current state"] const MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 ; # [doc = "hi-power peripheral supply is in over-current state"] const MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 ; # [doc = "Power status has changed since boot"] const MAV_POWER_STATUS_CHANGED = 32 ; } }
4087impl MavPowerStatus {
4088 pub const DEFAULT: Self = Self::MAV_POWER_STATUS_BRICK_VALID;
4089}
4090impl Default for MavPowerStatus {
4091 fn default() -> Self {
4092 Self::DEFAULT
4093 }
4094}
4095#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4096#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4097#[cfg_attr(feature = "serde", serde(tag = "type"))]
4098#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4099#[repr(u32)]
4100#[doc = "GPS longitudinal offset encoding"]
4101pub enum UavionixAdsbOutCfgGpsOffsetLon {
4102 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_NO_DATA = 0,
4103 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_APPLIED_BY_SENSOR = 1,
4104}
4105impl UavionixAdsbOutCfgGpsOffsetLon {
4106 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_NO_DATA;
4107}
4108impl Default for UavionixAdsbOutCfgGpsOffsetLon {
4109 fn default() -> Self {
4110 Self::DEFAULT
4111 }
4112}
4113#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4114#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4115#[cfg_attr(feature = "serde", serde(tag = "type"))]
4116#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4117#[repr(u32)]
4118#[doc = "Reason for an event error response."]
4119pub enum MavEventErrorReason {
4120 #[doc = "The requested event is not available (anymore)."]
4121 MAV_EVENT_ERROR_REASON_UNAVAILABLE = 0,
4122}
4123impl MavEventErrorReason {
4124 pub const DEFAULT: Self = Self::MAV_EVENT_ERROR_REASON_UNAVAILABLE;
4125}
4126impl Default for MavEventErrorReason {
4127 fn default() -> Self {
4128 Self::DEFAULT
4129 }
4130}
4131#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4132#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4133#[cfg_attr(feature = "serde", serde(tag = "type"))]
4134#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4135#[repr(u32)]
4136pub enum MavOdidArmStatus {
4137 #[doc = "Passing arming checks."]
4138 MAV_ODID_ARM_STATUS_GOOD_TO_ARM = 0,
4139 #[doc = "Generic arming failure, see error string for details."]
4140 MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC = 1,
4141}
4142impl MavOdidArmStatus {
4143 pub const DEFAULT: Self = Self::MAV_ODID_ARM_STATUS_GOOD_TO_ARM;
4144}
4145impl Default for MavOdidArmStatus {
4146 fn default() -> Self {
4147 Self::DEFAULT
4148 }
4149}
4150#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4151#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4152#[cfg_attr(feature = "serde", serde(tag = "type"))]
4153#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4154#[repr(u32)]
4155pub enum MavOdidClassEu {
4156 #[doc = "The class for the UA, according to the EU specification, is undeclared."]
4157 MAV_ODID_CLASS_EU_UNDECLARED = 0,
4158 #[doc = "The class for the UA, according to the EU specification, is Class 0."]
4159 MAV_ODID_CLASS_EU_CLASS_0 = 1,
4160 #[doc = "The class for the UA, according to the EU specification, is Class 1."]
4161 MAV_ODID_CLASS_EU_CLASS_1 = 2,
4162 #[doc = "The class for the UA, according to the EU specification, is Class 2."]
4163 MAV_ODID_CLASS_EU_CLASS_2 = 3,
4164 #[doc = "The class for the UA, according to the EU specification, is Class 3."]
4165 MAV_ODID_CLASS_EU_CLASS_3 = 4,
4166 #[doc = "The class for the UA, according to the EU specification, is Class 4."]
4167 MAV_ODID_CLASS_EU_CLASS_4 = 5,
4168 #[doc = "The class for the UA, according to the EU specification, is Class 5."]
4169 MAV_ODID_CLASS_EU_CLASS_5 = 6,
4170 #[doc = "The class for the UA, according to the EU specification, is Class 6."]
4171 MAV_ODID_CLASS_EU_CLASS_6 = 7,
4172}
4173impl MavOdidClassEu {
4174 pub const DEFAULT: Self = Self::MAV_ODID_CLASS_EU_UNDECLARED;
4175}
4176impl Default for MavOdidClassEu {
4177 fn default() -> Self {
4178 Self::DEFAULT
4179 }
4180}
4181#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4182#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4183#[cfg_attr(feature = "serde", serde(tag = "type"))]
4184#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4185#[repr(u32)]
4186#[doc = "Gripper actions."]
4187pub enum GripperActions {
4188 #[doc = "Gripper release cargo."]
4189 GRIPPER_ACTION_RELEASE = 0,
4190 #[doc = "Gripper grab onto cargo."]
4191 GRIPPER_ACTION_GRAB = 1,
4192}
4193impl GripperActions {
4194 pub const DEFAULT: Self = Self::GRIPPER_ACTION_RELEASE;
4195}
4196impl Default for GripperActions {
4197 fn default() -> Self {
4198 Self::DEFAULT
4199 }
4200}
4201bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Winch status flags used in WINCH_STATUS"] pub struct MavWinchStatusFlag : u32 { # [doc = "Winch is healthy"] const MAV_WINCH_STATUS_HEALTHY = 1 ; # [doc = "Winch line is fully retracted"] const MAV_WINCH_STATUS_FULLY_RETRACTED = 2 ; # [doc = "Winch motor is moving"] const MAV_WINCH_STATUS_MOVING = 4 ; # [doc = "Winch clutch is engaged allowing motor to move freely."] const MAV_WINCH_STATUS_CLUTCH_ENGAGED = 8 ; # [doc = "Winch is locked by locking mechanism."] const MAV_WINCH_STATUS_LOCKED = 16 ; # [doc = "Winch is gravity dropping payload."] const MAV_WINCH_STATUS_DROPPING = 32 ; # [doc = "Winch is arresting payload descent."] const MAV_WINCH_STATUS_ARRESTING = 64 ; # [doc = "Winch is using torque measurements to sense the ground."] const MAV_WINCH_STATUS_GROUND_SENSE = 128 ; # [doc = "Winch is returning to the fully retracted position."] const MAV_WINCH_STATUS_RETRACTING = 256 ; # [doc = "Winch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING."] const MAV_WINCH_STATUS_REDELIVER = 512 ; # [doc = "Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold."] const MAV_WINCH_STATUS_ABANDON_LINE = 1024 ; # [doc = "Winch is engaging the locking mechanism."] const MAV_WINCH_STATUS_LOCKING = 2048 ; # [doc = "Winch is spooling on line."] const MAV_WINCH_STATUS_LOAD_LINE = 4096 ; # [doc = "Winch is loading a payload."] const MAV_WINCH_STATUS_LOAD_PAYLOAD = 8192 ; } }
4202impl MavWinchStatusFlag {
4203 pub const DEFAULT: Self = Self::MAV_WINCH_STATUS_HEALTHY;
4204}
4205impl Default for MavWinchStatusFlag {
4206 fn default() -> Self {
4207 Self::DEFAULT
4208 }
4209}
4210#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4211#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4212#[cfg_attr(feature = "serde", serde(tag = "type"))]
4213#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4214#[repr(u32)]
4215pub enum MavOdidHeightRef {
4216 #[doc = "The height field is relative to the take-off location."]
4217 MAV_ODID_HEIGHT_REF_OVER_TAKEOFF = 0,
4218 #[doc = "The height field is relative to ground."]
4219 MAV_ODID_HEIGHT_REF_OVER_GROUND = 1,
4220}
4221impl MavOdidHeightRef {
4222 pub const DEFAULT: Self = Self::MAV_ODID_HEIGHT_REF_OVER_TAKEOFF;
4223}
4224impl Default for MavOdidHeightRef {
4225 fn default() -> Self {
4226 Self::DEFAULT
4227 }
4228}
4229#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4230#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4231#[cfg_attr(feature = "serde", serde(tag = "type"))]
4232#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4233#[repr(u32)]
4234#[doc = "Camera sources for MAV_CMD_SET_CAMERA_SOURCE"]
4235pub enum CameraSource {
4236 #[doc = "Default camera source."]
4237 CAMERA_SOURCE_DEFAULT = 0,
4238 #[doc = "RGB camera source."]
4239 CAMERA_SOURCE_RGB = 1,
4240 #[doc = "IR camera source."]
4241 CAMERA_SOURCE_IR = 2,
4242 #[doc = "NDVI camera source."]
4243 CAMERA_SOURCE_NDVI = 3,
4244}
4245impl CameraSource {
4246 pub const DEFAULT: Self = Self::CAMERA_SOURCE_DEFAULT;
4247}
4248impl Default for CameraSource {
4249 fn default() -> Self {
4250 Self::DEFAULT
4251 }
4252}
4253bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Status flags for ADS-B transponder dynamic output"] pub struct UavionixAdsbRfHealth : u8 { const UAVIONIX_ADSB_RF_HEALTH_OK = 1 ; const UAVIONIX_ADSB_RF_HEALTH_FAIL_TX = 2 ; const UAVIONIX_ADSB_RF_HEALTH_FAIL_RX = 16 ; } }
4254impl UavionixAdsbRfHealth {
4255 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_RF_HEALTH_OK;
4256}
4257impl Default for UavionixAdsbRfHealth {
4258 fn default() -> Self {
4259 Self::DEFAULT
4260 }
4261}
4262bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability."] pub struct MavProtocolCapability : u64 { # [doc = "Autopilot supports the MISSION_ITEM float message type. Note that MISSION_ITEM is deprecated, and autopilots should use MISSION_INT instead."] const MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 ; # [doc = "Autopilot supports the new param float message type."] const MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 ; # [doc = "Autopilot supports MISSION_ITEM_INT scaled integer message type. Note that this flag must always be set if missions are supported, because missions must always use MISSION_ITEM_INT (rather than MISSION_ITEM, which is deprecated)."] const MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 ; # [doc = "Autopilot supports COMMAND_INT scaled integer message type."] const MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 ; # [doc = "Parameter protocol uses byte-wise encoding of parameter values into param_value (float) fields: <https://mavlink.io/en/services/parameter.html#parameter-encoding>. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST should be set if the parameter protocol is supported."] const MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE = 16 ; # [doc = "Autopilot supports the File Transfer Protocol v1: <https://mavlink.io/en/services/ftp.html>."] const MAV_PROTOCOL_CAPABILITY_FTP = 32 ; # [doc = "Autopilot supports commanding attitude offboard."] const MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 ; # [doc = "Autopilot supports commanding position and velocity targets in local NED frame."] const MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 ; # [doc = "Autopilot supports commanding position and velocity targets in global scaled integers."] const MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 ; # [doc = "Autopilot supports terrain protocol / data handling."] const MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 ; # [doc = "Reserved for future use."] const MAV_PROTOCOL_CAPABILITY_RESERVED3 = 1024 ; # [doc = "Autopilot supports the MAV_CMD_DO_FLIGHTTERMINATION command (flight termination)."] const MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 ; # [doc = "Autopilot supports onboard compass calibration."] const MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 ; # [doc = "Autopilot supports MAVLink version 2."] const MAV_PROTOCOL_CAPABILITY_MAVLINK2 = 8192 ; # [doc = "Autopilot supports mission fence protocol."] const MAV_PROTOCOL_CAPABILITY_MISSION_FENCE = 16384 ; # [doc = "Autopilot supports mission rally point protocol."] const MAV_PROTOCOL_CAPABILITY_MISSION_RALLY = 32768 ; # [doc = "Reserved for future use."] const MAV_PROTOCOL_CAPABILITY_RESERVED2 = 65536 ; # [doc = "Parameter protocol uses C-cast of parameter values to set the param_value (float) fields: <https://mavlink.io/en/services/parameter.html#parameter-encoding>. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE should be set if the parameter protocol is supported."] const MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST = 131072 ; # [doc = "This component implements/is a gimbal manager. This means the GIMBAL_MANAGER_INFORMATION, and other messages can be requested."] const MAV_PROTOCOL_CAPABILITY_COMPONENT_IMPLEMENTS_GIMBAL_MANAGER = 262144 ; # [doc = "Component supports locking control to a particular GCS independent of its system (via MAV_CMD_REQUEST_OPERATOR_CONTROL)."] const MAV_PROTOCOL_CAPABILITY_COMPONENT_ACCEPTS_GCS_CONTROL = 524288 ; } }
4263impl MavProtocolCapability {
4264 pub const DEFAULT: Self = Self::MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT;
4265}
4266impl Default for MavProtocolCapability {
4267 fn default() -> Self {
4268 Self::DEFAULT
4269 }
4270}
4271#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4272#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4273#[cfg_attr(feature = "serde", serde(tag = "type"))]
4274#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4275#[repr(u32)]
4276pub enum MavArmAuthDeniedReason {
4277 #[doc = "Not a specific reason"]
4278 MAV_ARM_AUTH_DENIED_REASON_GENERIC = 0,
4279 #[doc = "Authorizer will send the error as string to GCS"]
4280 MAV_ARM_AUTH_DENIED_REASON_NONE = 1,
4281 #[doc = "At least one waypoint have a invalid value"]
4282 MAV_ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT = 2,
4283 #[doc = "Timeout in the authorizer process(in case it depends on network)"]
4284 MAV_ARM_AUTH_DENIED_REASON_TIMEOUT = 3,
4285 #[doc = "Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied."]
4286 MAV_ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE = 4,
4287 #[doc = "Weather is not good to fly"]
4288 MAV_ARM_AUTH_DENIED_REASON_BAD_WEATHER = 5,
4289}
4290impl MavArmAuthDeniedReason {
4291 pub const DEFAULT: Self = Self::MAV_ARM_AUTH_DENIED_REASON_GENERIC;
4292}
4293impl Default for MavArmAuthDeniedReason {
4294 fn default() -> Self {
4295 Self::DEFAULT
4296 }
4297}
4298#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4299#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4300#[cfg_attr(feature = "serde", serde(tag = "type"))]
4301#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4302#[repr(u32)]
4303#[doc = "Airborne status of UAS."]
4304pub enum UtmFlightState {
4305 #[doc = "The flight state can't be determined."]
4306 UTM_FLIGHT_STATE_UNKNOWN = 1,
4307 #[doc = "UAS on ground."]
4308 UTM_FLIGHT_STATE_GROUND = 2,
4309 #[doc = "UAS airborne."]
4310 UTM_FLIGHT_STATE_AIRBORNE = 3,
4311 #[doc = "UAS is in an emergency flight state."]
4312 UTM_FLIGHT_STATE_EMERGENCY = 16,
4313 #[doc = "UAS has no active controls."]
4314 UTM_FLIGHT_STATE_NOCTRL = 32,
4315}
4316impl UtmFlightState {
4317 pub const DEFAULT: Self = Self::UTM_FLIGHT_STATE_UNKNOWN;
4318}
4319impl Default for UtmFlightState {
4320 fn default() -> Self {
4321 Self::DEFAULT
4322 }
4323}
4324#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4325#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4326#[cfg_attr(feature = "serde", serde(tag = "type"))]
4327#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4328#[repr(u32)]
4329#[doc = "Type of landing target"]
4330pub enum LandingTargetType {
4331 #[doc = "Landing target signaled by light beacon (ex: IR-LOCK)"]
4332 LANDING_TARGET_TYPE_LIGHT_BEACON = 0,
4333 #[doc = "Landing target signaled by radio beacon (ex: ILS, NDB)"]
4334 LANDING_TARGET_TYPE_RADIO_BEACON = 1,
4335 #[doc = "Landing target represented by a fiducial marker (ex: ARTag)"]
4336 LANDING_TARGET_TYPE_VISION_FIDUCIAL = 2,
4337 #[doc = "Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)"]
4338 LANDING_TARGET_TYPE_VISION_OTHER = 3,
4339}
4340impl LandingTargetType {
4341 pub const DEFAULT: Self = Self::LANDING_TARGET_TYPE_LIGHT_BEACON;
4342}
4343impl Default for LandingTargetType {
4344 fn default() -> Self {
4345 Self::DEFAULT
4346 }
4347}
4348#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4349#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4350#[cfg_attr(feature = "serde", serde(tag = "type"))]
4351#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4352#[repr(u32)]
4353#[doc = "ADSB classification for the type of vehicle emitting the transponder signal"]
4354pub enum AdsbEmitterType {
4355 ADSB_EMITTER_TYPE_NO_INFO = 0,
4356 ADSB_EMITTER_TYPE_LIGHT = 1,
4357 ADSB_EMITTER_TYPE_SMALL = 2,
4358 ADSB_EMITTER_TYPE_LARGE = 3,
4359 ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4,
4360 ADSB_EMITTER_TYPE_HEAVY = 5,
4361 ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6,
4362 ADSB_EMITTER_TYPE_ROTOCRAFT = 7,
4363 ADSB_EMITTER_TYPE_UNASSIGNED = 8,
4364 ADSB_EMITTER_TYPE_GLIDER = 9,
4365 ADSB_EMITTER_TYPE_LIGHTER_AIR = 10,
4366 ADSB_EMITTER_TYPE_PARACHUTE = 11,
4367 ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12,
4368 ADSB_EMITTER_TYPE_UNASSIGNED2 = 13,
4369 ADSB_EMITTER_TYPE_UAV = 14,
4370 ADSB_EMITTER_TYPE_SPACE = 15,
4371 ADSB_EMITTER_TYPE_UNASSGINED3 = 16,
4372 ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17,
4373 ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18,
4374 ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19,
4375}
4376impl AdsbEmitterType {
4377 pub const DEFAULT: Self = Self::ADSB_EMITTER_TYPE_NO_INFO;
4378}
4379impl Default for AdsbEmitterType {
4380 fn default() -> Self {
4381 Self::DEFAULT
4382 }
4383}
4384#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4385#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4386#[cfg_attr(feature = "serde", serde(tag = "type"))]
4387#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4388#[repr(u32)]
4389pub enum MavOdidHorAcc {
4390 #[doc = "The horizontal accuracy is unknown."]
4391 MAV_ODID_HOR_ACC_UNKNOWN = 0,
4392 #[doc = "The horizontal accuracy is smaller than 10 Nautical Miles. 18.52 km."]
4393 MAV_ODID_HOR_ACC_10NM = 1,
4394 #[doc = "The horizontal accuracy is smaller than 4 Nautical Miles. 7.408 km."]
4395 MAV_ODID_HOR_ACC_4NM = 2,
4396 #[doc = "The horizontal accuracy is smaller than 2 Nautical Miles. 3.704 km."]
4397 MAV_ODID_HOR_ACC_2NM = 3,
4398 #[doc = "The horizontal accuracy is smaller than 1 Nautical Miles. 1.852 km."]
4399 MAV_ODID_HOR_ACC_1NM = 4,
4400 #[doc = "The horizontal accuracy is smaller than 0.5 Nautical Miles. 926 m."]
4401 MAV_ODID_HOR_ACC_0_5NM = 5,
4402 #[doc = "The horizontal accuracy is smaller than 0.3 Nautical Miles. 555.6 m."]
4403 MAV_ODID_HOR_ACC_0_3NM = 6,
4404 #[doc = "The horizontal accuracy is smaller than 0.1 Nautical Miles. 185.2 m."]
4405 MAV_ODID_HOR_ACC_0_1NM = 7,
4406 #[doc = "The horizontal accuracy is smaller than 0.05 Nautical Miles. 92.6 m."]
4407 MAV_ODID_HOR_ACC_0_05NM = 8,
4408 #[doc = "The horizontal accuracy is smaller than 30 meter."]
4409 MAV_ODID_HOR_ACC_30_METER = 9,
4410 #[doc = "The horizontal accuracy is smaller than 10 meter."]
4411 MAV_ODID_HOR_ACC_10_METER = 10,
4412 #[doc = "The horizontal accuracy is smaller than 3 meter."]
4413 MAV_ODID_HOR_ACC_3_METER = 11,
4414 #[doc = "The horizontal accuracy is smaller than 1 meter."]
4415 MAV_ODID_HOR_ACC_1_METER = 12,
4416}
4417impl MavOdidHorAcc {
4418 pub const DEFAULT: Self = Self::MAV_ODID_HOR_ACC_UNKNOWN;
4419}
4420impl Default for MavOdidHorAcc {
4421 fn default() -> Self {
4422 Self::DEFAULT
4423 }
4424}
4425bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report ESC failures."] pub struct EscFailureFlags : u16 { # [doc = "Over current failure."] const ESC_FAILURE_OVER_CURRENT = 1 ; # [doc = "Over voltage failure."] const ESC_FAILURE_OVER_VOLTAGE = 2 ; # [doc = "Over temperature failure."] const ESC_FAILURE_OVER_TEMPERATURE = 4 ; # [doc = "Over RPM failure."] const ESC_FAILURE_OVER_RPM = 8 ; # [doc = "Inconsistent command failure i.e. out of bounds."] const ESC_FAILURE_INCONSISTENT_CMD = 16 ; # [doc = "Motor stuck failure."] const ESC_FAILURE_MOTOR_STUCK = 32 ; # [doc = "Generic ESC failure."] const ESC_FAILURE_GENERIC = 64 ; } }
4426impl EscFailureFlags {
4427 pub const DEFAULT: Self = Self::ESC_FAILURE_OVER_CURRENT;
4428}
4429impl Default for EscFailureFlags {
4430 fn default() -> Self {
4431 Self::DEFAULT
4432 }
4433}
4434#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4435#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4436#[cfg_attr(feature = "serde", serde(tag = "type"))]
4437#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4438#[repr(u32)]
4439#[doc = "Focus types for MAV_CMD_SET_CAMERA_FOCUS"]
4440pub enum SetFocusType {
4441 #[doc = "Focus one step increment (-1 for focusing in, 1 for focusing out towards infinity)."]
4442 FOCUS_TYPE_STEP = 0,
4443 #[doc = "Continuous normalized focus in/out rate until stopped. Range -1..1, negative: in, positive: out towards infinity, 0 to stop focusing. Other values should be clipped to the range."]
4444 FOCUS_TYPE_CONTINUOUS = 1,
4445 #[doc = "Focus value as proportion of full camera focus range (a value between 0.0 and 100.0)"]
4446 FOCUS_TYPE_RANGE = 2,
4447 #[doc = "Focus value in metres. Note that there is no message to get the valid focus range of the camera, so this can type can only be used for cameras where the range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)."]
4448 FOCUS_TYPE_METERS = 3,
4449 #[doc = "Focus automatically."]
4450 FOCUS_TYPE_AUTO = 4,
4451 #[doc = "Single auto focus. Mainly used for still pictures. Usually abbreviated as AF-S."]
4452 FOCUS_TYPE_AUTO_SINGLE = 5,
4453 #[doc = "Continuous auto focus. Mainly used for dynamic scenes. Abbreviated as AF-C."]
4454 FOCUS_TYPE_AUTO_CONTINUOUS = 6,
4455}
4456impl SetFocusType {
4457 pub const DEFAULT: Self = Self::FOCUS_TYPE_STEP;
4458}
4459impl Default for SetFocusType {
4460 fn default() -> Self {
4461 Self::DEFAULT
4462 }
4463}
4464#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4465#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4466#[cfg_attr(feature = "serde", serde(tag = "type"))]
4467#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4468#[repr(u32)]
4469#[doc = "List of possible units where failures can be injected."]
4470pub enum FailureUnit {
4471 FAILURE_UNIT_SENSOR_GYRO = 0,
4472 FAILURE_UNIT_SENSOR_ACCEL = 1,
4473 FAILURE_UNIT_SENSOR_MAG = 2,
4474 FAILURE_UNIT_SENSOR_BARO = 3,
4475 FAILURE_UNIT_SENSOR_GPS = 4,
4476 FAILURE_UNIT_SENSOR_OPTICAL_FLOW = 5,
4477 FAILURE_UNIT_SENSOR_VIO = 6,
4478 FAILURE_UNIT_SENSOR_DISTANCE_SENSOR = 7,
4479 FAILURE_UNIT_SENSOR_AIRSPEED = 8,
4480 FAILURE_UNIT_SYSTEM_BATTERY = 100,
4481 FAILURE_UNIT_SYSTEM_MOTOR = 101,
4482 FAILURE_UNIT_SYSTEM_SERVO = 102,
4483 FAILURE_UNIT_SYSTEM_AVOIDANCE = 103,
4484 FAILURE_UNIT_SYSTEM_RC_SIGNAL = 104,
4485 FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL = 105,
4486}
4487impl FailureUnit {
4488 pub const DEFAULT: Self = Self::FAILURE_UNIT_SENSOR_GYRO;
4489}
4490impl Default for FailureUnit {
4491 fn default() -> Self {
4492 Self::DEFAULT
4493 }
4494}
4495#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4496#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4497#[cfg_attr(feature = "serde", serde(tag = "type"))]
4498#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4499#[repr(u32)]
4500#[doc = "Micro air vehicle / autopilot classes. This identifies the individual model."]
4501pub enum MavAutopilot {
4502 #[doc = "Generic autopilot, full support for everything"]
4503 MAV_AUTOPILOT_GENERIC = 0,
4504 #[doc = "Reserved for future use."]
4505 MAV_AUTOPILOT_RESERVED = 1,
4506 #[doc = "SLUGS autopilot, <http://slugsuav.soe.ucsc.edu>"]
4507 MAV_AUTOPILOT_SLUGS = 2,
4508 #[doc = "ArduPilot - Plane/Copter/Rover/Sub/Tracker, <https://ardupilot.org>"]
4509 MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
4510 #[doc = "OpenPilot, <http://openpilot.org>"]
4511 MAV_AUTOPILOT_OPENPILOT = 4,
4512 #[doc = "Generic autopilot only supporting simple waypoints"]
4513 MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5,
4514 #[doc = "Generic autopilot supporting waypoints and other simple navigation commands"]
4515 MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6,
4516 #[doc = "Generic autopilot supporting the full mission command set"]
4517 MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7,
4518 #[doc = "No valid autopilot, e.g. a GCS or other MAVLink component"]
4519 MAV_AUTOPILOT_INVALID = 8,
4520 #[doc = "PPZ UAV - <http://nongnu.org/paparazzi>"]
4521 MAV_AUTOPILOT_PPZ = 9,
4522 #[doc = "UAV Dev Board"]
4523 MAV_AUTOPILOT_UDB = 10,
4524 #[doc = "FlexiPilot"]
4525 MAV_AUTOPILOT_FP = 11,
4526 #[doc = "PX4 Autopilot - <http://px4.io/>"]
4527 MAV_AUTOPILOT_PX4 = 12,
4528 #[doc = "SMACCMPilot - <http://smaccmpilot.org>"]
4529 MAV_AUTOPILOT_SMACCMPILOT = 13,
4530 #[doc = "AutoQuad -- <http://autoquad.org>"]
4531 MAV_AUTOPILOT_AUTOQUAD = 14,
4532 #[doc = "Armazila -- <http://armazila.com>"]
4533 MAV_AUTOPILOT_ARMAZILA = 15,
4534 #[doc = "Aerob -- <http://aerob.ru>"]
4535 MAV_AUTOPILOT_AEROB = 16,
4536 #[doc = "ASLUAV autopilot -- <http://www.asl.ethz.ch>"]
4537 MAV_AUTOPILOT_ASLUAV = 17,
4538 #[doc = "SmartAP Autopilot - <http://sky-drones.com>"]
4539 MAV_AUTOPILOT_SMARTAP = 18,
4540 #[doc = "AirRails - <http://uaventure.com>"]
4541 MAV_AUTOPILOT_AIRRAILS = 19,
4542 #[doc = "Fusion Reflex - <https://fusion.engineering>"]
4543 MAV_AUTOPILOT_REFLEX = 20,
4544}
4545impl MavAutopilot {
4546 pub const DEFAULT: Self = Self::MAV_AUTOPILOT_GENERIC;
4547}
4548impl Default for MavAutopilot {
4549 fn default() -> Self {
4550 Self::DEFAULT
4551 }
4552}
4553bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Smart battery supply status/fault flags (bitmask) for health indication. The battery must also report either MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY if any of these are set."] pub struct MavBatteryFault : u32 { # [doc = "Battery has deep discharged."] const MAV_BATTERY_FAULT_DEEP_DISCHARGE = 1 ; # [doc = "Voltage spikes."] const MAV_BATTERY_FAULT_SPIKES = 2 ; # [doc = "One or more cells have failed. Battery should also report MAV_BATTERY_CHARGE_STATE_FAILE (and should not be used)."] const MAV_BATTERY_FAULT_CELL_FAIL = 4 ; # [doc = "Over-current fault."] const MAV_BATTERY_FAULT_OVER_CURRENT = 8 ; # [doc = "Over-temperature fault."] const MAV_BATTERY_FAULT_OVER_TEMPERATURE = 16 ; # [doc = "Under-temperature fault."] const MAV_BATTERY_FAULT_UNDER_TEMPERATURE = 32 ; # [doc = "Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage)."] const MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = 64 ; # [doc = "Battery firmware is not compatible with current autopilot firmware."] const MAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = 128 ; # [doc = "Battery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s)."] const BATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION = 256 ; } }
4554impl MavBatteryFault {
4555 pub const DEFAULT: Self = Self::MAV_BATTERY_FAULT_DEEP_DISCHARGE;
4556}
4557impl Default for MavBatteryFault {
4558 fn default() -> Self {
4559 Self::DEFAULT
4560 }
4561}
4562#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4563#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4564#[cfg_attr(feature = "serde", serde(tag = "type"))]
4565#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4566#[repr(u32)]
4567#[doc = "Result from PARAM_EXT_SET message."]
4568pub enum ParamAck {
4569 #[doc = "Parameter value ACCEPTED and SET"]
4570 PARAM_ACK_ACCEPTED = 0,
4571 #[doc = "Parameter value UNKNOWN/UNSUPPORTED"]
4572 PARAM_ACK_VALUE_UNSUPPORTED = 1,
4573 #[doc = "Parameter failed to set"]
4574 PARAM_ACK_FAILED = 2,
4575 #[doc = "Parameter value received but not yet set/accepted. A subsequent PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent."]
4576 PARAM_ACK_IN_PROGRESS = 3,
4577}
4578impl ParamAck {
4579 pub const DEFAULT: Self = Self::PARAM_ACK_ACCEPTED;
4580}
4581impl Default for ParamAck {
4582 fn default() -> Self {
4583 Self::DEFAULT
4584 }
4585}
4586#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4587#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4588#[cfg_attr(feature = "serde", serde(tag = "type"))]
4589#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4590#[repr(u32)]
4591#[doc = "Navigational status of AIS vessel, enum duplicated from AIS standard, <https://gpsd.gitlab.io/gpsd/AIVDM.html>"]
4592pub enum AisNavStatus {
4593 #[doc = "Under way using engine."]
4594 UNDER_WAY = 0,
4595 AIS_NAV_ANCHORED = 1,
4596 AIS_NAV_UN_COMMANDED = 2,
4597 AIS_NAV_RESTRICTED_MANOEUVERABILITY = 3,
4598 AIS_NAV_DRAUGHT_CONSTRAINED = 4,
4599 AIS_NAV_MOORED = 5,
4600 AIS_NAV_AGROUND = 6,
4601 AIS_NAV_FISHING = 7,
4602 AIS_NAV_SAILING = 8,
4603 AIS_NAV_RESERVED_HSC = 9,
4604 AIS_NAV_RESERVED_WIG = 10,
4605 AIS_NAV_RESERVED_1 = 11,
4606 AIS_NAV_RESERVED_2 = 12,
4607 AIS_NAV_RESERVED_3 = 13,
4608 #[doc = "Search And Rescue Transponder."]
4609 AIS_NAV_AIS_SART = 14,
4610 #[doc = "Not available (default)."]
4611 AIS_NAV_UNKNOWN = 15,
4612}
4613impl AisNavStatus {
4614 pub const DEFAULT: Self = Self::UNDER_WAY;
4615}
4616impl Default for AisNavStatus {
4617 fn default() -> Self {
4618 Self::DEFAULT
4619 }
4620}
4621#[doc = "id: 140"]
4622#[doc = "Set the vehicle attitude and body angular rates."]
4623#[derive(Debug, Clone, PartialEq)]
4624#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4625#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4626pub struct ACTUATOR_CONTROL_TARGET_DATA {
4627 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
4628 pub time_usec: u64,
4629 #[doc = "Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs."]
4630 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
4631 pub controls: [f32; 8],
4632 #[doc = "Actuator group. The \"_mlx\" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances."]
4633 pub group_mlx: u8,
4634}
4635impl ACTUATOR_CONTROL_TARGET_DATA {
4636 pub const ENCODED_LEN: usize = 41usize;
4637 pub const DEFAULT: Self = Self {
4638 time_usec: 0_u64,
4639 controls: [0.0_f32; 8usize],
4640 group_mlx: 0_u8,
4641 };
4642 #[cfg(feature = "arbitrary")]
4643 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4644 use arbitrary::{Arbitrary, Unstructured};
4645 let mut buf = [0u8; 1024];
4646 rng.fill_bytes(&mut buf);
4647 let mut unstructured = Unstructured::new(&buf);
4648 Self::arbitrary(&mut unstructured).unwrap_or_default()
4649 }
4650}
4651impl Default for ACTUATOR_CONTROL_TARGET_DATA {
4652 fn default() -> Self {
4653 Self::DEFAULT.clone()
4654 }
4655}
4656impl MessageData for ACTUATOR_CONTROL_TARGET_DATA {
4657 type Message = MavMessage;
4658 const ID: u32 = 140u32;
4659 const NAME: &'static str = "ACTUATOR_CONTROL_TARGET";
4660 const EXTRA_CRC: u8 = 181u8;
4661 const ENCODED_LEN: usize = 41usize;
4662 fn deser(
4663 _version: MavlinkVersion,
4664 __input: &[u8],
4665 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4666 let avail_len = __input.len();
4667 let mut payload_buf = [0; Self::ENCODED_LEN];
4668 let mut buf = if avail_len < Self::ENCODED_LEN {
4669 payload_buf[0..avail_len].copy_from_slice(__input);
4670 Bytes::new(&payload_buf)
4671 } else {
4672 Bytes::new(__input)
4673 };
4674 let mut __struct = Self::default();
4675 __struct.time_usec = buf.get_u64_le();
4676 for v in &mut __struct.controls {
4677 let val = buf.get_f32_le();
4678 *v = val;
4679 }
4680 __struct.group_mlx = buf.get_u8();
4681 Ok(__struct)
4682 }
4683 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4684 let mut __tmp = BytesMut::new(bytes);
4685 #[allow(clippy::absurd_extreme_comparisons)]
4686 #[allow(unused_comparisons)]
4687 if __tmp.remaining() < Self::ENCODED_LEN {
4688 panic!(
4689 "buffer is too small (need {} bytes, but got {})",
4690 Self::ENCODED_LEN,
4691 __tmp.remaining(),
4692 )
4693 }
4694 __tmp.put_u64_le(self.time_usec);
4695 for val in &self.controls {
4696 __tmp.put_f32_le(*val);
4697 }
4698 __tmp.put_u8(self.group_mlx);
4699 if matches!(version, MavlinkVersion::V2) {
4700 let len = __tmp.len();
4701 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4702 } else {
4703 __tmp.len()
4704 }
4705 }
4706}
4707#[doc = "id: 121"]
4708#[doc = "Erase all logs."]
4709#[derive(Debug, Clone, PartialEq)]
4710#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4711#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4712pub struct LOG_ERASE_DATA {
4713 #[doc = "System ID"]
4714 pub target_system: u8,
4715 #[doc = "Component ID"]
4716 pub target_component: u8,
4717}
4718impl LOG_ERASE_DATA {
4719 pub const ENCODED_LEN: usize = 2usize;
4720 pub const DEFAULT: Self = Self {
4721 target_system: 0_u8,
4722 target_component: 0_u8,
4723 };
4724 #[cfg(feature = "arbitrary")]
4725 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4726 use arbitrary::{Arbitrary, Unstructured};
4727 let mut buf = [0u8; 1024];
4728 rng.fill_bytes(&mut buf);
4729 let mut unstructured = Unstructured::new(&buf);
4730 Self::arbitrary(&mut unstructured).unwrap_or_default()
4731 }
4732}
4733impl Default for LOG_ERASE_DATA {
4734 fn default() -> Self {
4735 Self::DEFAULT.clone()
4736 }
4737}
4738impl MessageData for LOG_ERASE_DATA {
4739 type Message = MavMessage;
4740 const ID: u32 = 121u32;
4741 const NAME: &'static str = "LOG_ERASE";
4742 const EXTRA_CRC: u8 = 237u8;
4743 const ENCODED_LEN: usize = 2usize;
4744 fn deser(
4745 _version: MavlinkVersion,
4746 __input: &[u8],
4747 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4748 let avail_len = __input.len();
4749 let mut payload_buf = [0; Self::ENCODED_LEN];
4750 let mut buf = if avail_len < Self::ENCODED_LEN {
4751 payload_buf[0..avail_len].copy_from_slice(__input);
4752 Bytes::new(&payload_buf)
4753 } else {
4754 Bytes::new(__input)
4755 };
4756 let mut __struct = Self::default();
4757 __struct.target_system = buf.get_u8();
4758 __struct.target_component = buf.get_u8();
4759 Ok(__struct)
4760 }
4761 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4762 let mut __tmp = BytesMut::new(bytes);
4763 #[allow(clippy::absurd_extreme_comparisons)]
4764 #[allow(unused_comparisons)]
4765 if __tmp.remaining() < Self::ENCODED_LEN {
4766 panic!(
4767 "buffer is too small (need {} bytes, but got {})",
4768 Self::ENCODED_LEN,
4769 __tmp.remaining(),
4770 )
4771 }
4772 __tmp.put_u8(self.target_system);
4773 __tmp.put_u8(self.target_component);
4774 if matches!(version, MavlinkVersion::V2) {
4775 let len = __tmp.len();
4776 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4777 } else {
4778 __tmp.len()
4779 }
4780 }
4781}
4782#[doc = "id: 275"]
4783#[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval."]
4784#[derive(Debug, Clone, PartialEq)]
4785#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4786#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4787pub struct CAMERA_TRACKING_IMAGE_STATUS_DATA {
4788 #[doc = "Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
4789 pub point_x: f32,
4790 #[doc = "Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
4791 pub point_y: f32,
4792 #[doc = "Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown"]
4793 pub radius: f32,
4794 #[doc = "Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
4795 pub rec_top_x: f32,
4796 #[doc = "Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
4797 pub rec_top_y: f32,
4798 #[doc = "Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
4799 pub rec_bottom_x: f32,
4800 #[doc = "Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
4801 pub rec_bottom_y: f32,
4802 #[doc = "Current tracking status"]
4803 pub tracking_status: CameraTrackingStatusFlags,
4804 #[doc = "Current tracking mode"]
4805 pub tracking_mode: CameraTrackingMode,
4806 #[doc = "Defines location of target data"]
4807 pub target_data: CameraTrackingTargetData,
4808 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
4809 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4810 pub camera_device_id: u8,
4811}
4812impl CAMERA_TRACKING_IMAGE_STATUS_DATA {
4813 pub const ENCODED_LEN: usize = 32usize;
4814 pub const DEFAULT: Self = Self {
4815 point_x: 0.0_f32,
4816 point_y: 0.0_f32,
4817 radius: 0.0_f32,
4818 rec_top_x: 0.0_f32,
4819 rec_top_y: 0.0_f32,
4820 rec_bottom_x: 0.0_f32,
4821 rec_bottom_y: 0.0_f32,
4822 tracking_status: CameraTrackingStatusFlags::DEFAULT,
4823 tracking_mode: CameraTrackingMode::DEFAULT,
4824 target_data: CameraTrackingTargetData::DEFAULT,
4825 camera_device_id: 0_u8,
4826 };
4827 #[cfg(feature = "arbitrary")]
4828 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4829 use arbitrary::{Arbitrary, Unstructured};
4830 let mut buf = [0u8; 1024];
4831 rng.fill_bytes(&mut buf);
4832 let mut unstructured = Unstructured::new(&buf);
4833 Self::arbitrary(&mut unstructured).unwrap_or_default()
4834 }
4835}
4836impl Default for CAMERA_TRACKING_IMAGE_STATUS_DATA {
4837 fn default() -> Self {
4838 Self::DEFAULT.clone()
4839 }
4840}
4841impl MessageData for CAMERA_TRACKING_IMAGE_STATUS_DATA {
4842 type Message = MavMessage;
4843 const ID: u32 = 275u32;
4844 const NAME: &'static str = "CAMERA_TRACKING_IMAGE_STATUS";
4845 const EXTRA_CRC: u8 = 126u8;
4846 const ENCODED_LEN: usize = 32usize;
4847 fn deser(
4848 _version: MavlinkVersion,
4849 __input: &[u8],
4850 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4851 let avail_len = __input.len();
4852 let mut payload_buf = [0; Self::ENCODED_LEN];
4853 let mut buf = if avail_len < Self::ENCODED_LEN {
4854 payload_buf[0..avail_len].copy_from_slice(__input);
4855 Bytes::new(&payload_buf)
4856 } else {
4857 Bytes::new(__input)
4858 };
4859 let mut __struct = Self::default();
4860 __struct.point_x = buf.get_f32_le();
4861 __struct.point_y = buf.get_f32_le();
4862 __struct.radius = buf.get_f32_le();
4863 __struct.rec_top_x = buf.get_f32_le();
4864 __struct.rec_top_y = buf.get_f32_le();
4865 __struct.rec_bottom_x = buf.get_f32_le();
4866 __struct.rec_bottom_y = buf.get_f32_le();
4867 let tmp = buf.get_u8();
4868 __struct.tracking_status =
4869 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
4870 enum_type: "CameraTrackingStatusFlags",
4871 value: tmp as u32,
4872 })?;
4873 let tmp = buf.get_u8();
4874 __struct.tracking_mode =
4875 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
4876 enum_type: "CameraTrackingMode",
4877 value: tmp as u32,
4878 })?;
4879 let tmp = buf.get_u8();
4880 __struct.target_data =
4881 CameraTrackingTargetData::from_bits(tmp & CameraTrackingTargetData::all().bits())
4882 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
4883 flag_type: "CameraTrackingTargetData",
4884 value: tmp as u32,
4885 })?;
4886 __struct.camera_device_id = buf.get_u8();
4887 Ok(__struct)
4888 }
4889 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4890 let mut __tmp = BytesMut::new(bytes);
4891 #[allow(clippy::absurd_extreme_comparisons)]
4892 #[allow(unused_comparisons)]
4893 if __tmp.remaining() < Self::ENCODED_LEN {
4894 panic!(
4895 "buffer is too small (need {} bytes, but got {})",
4896 Self::ENCODED_LEN,
4897 __tmp.remaining(),
4898 )
4899 }
4900 __tmp.put_f32_le(self.point_x);
4901 __tmp.put_f32_le(self.point_y);
4902 __tmp.put_f32_le(self.radius);
4903 __tmp.put_f32_le(self.rec_top_x);
4904 __tmp.put_f32_le(self.rec_top_y);
4905 __tmp.put_f32_le(self.rec_bottom_x);
4906 __tmp.put_f32_le(self.rec_bottom_y);
4907 __tmp.put_u8(self.tracking_status as u8);
4908 __tmp.put_u8(self.tracking_mode as u8);
4909 __tmp.put_u8(self.target_data.bits());
4910 __tmp.put_u8(self.camera_device_id);
4911 if matches!(version, MavlinkVersion::V2) {
4912 let len = __tmp.len();
4913 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4914 } else {
4915 __tmp.len()
4916 }
4917 }
4918}
4919#[doc = "id: 38"]
4920#[doc = "This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!."]
4921#[derive(Debug, Clone, PartialEq)]
4922#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4923#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4924pub struct MISSION_WRITE_PARTIAL_LIST_DATA {
4925 #[doc = "Start index. Must be smaller / equal to the largest index of the current onboard list."]
4926 pub start_index: i16,
4927 #[doc = "End index, equal or greater than start index."]
4928 pub end_index: i16,
4929 #[doc = "System ID"]
4930 pub target_system: u8,
4931 #[doc = "Component ID"]
4932 pub target_component: u8,
4933 #[doc = "Mission type."]
4934 #[cfg_attr(feature = "serde", serde(default))]
4935 pub mission_type: MavMissionType,
4936}
4937impl MISSION_WRITE_PARTIAL_LIST_DATA {
4938 pub const ENCODED_LEN: usize = 7usize;
4939 pub const DEFAULT: Self = Self {
4940 start_index: 0_i16,
4941 end_index: 0_i16,
4942 target_system: 0_u8,
4943 target_component: 0_u8,
4944 mission_type: MavMissionType::DEFAULT,
4945 };
4946 #[cfg(feature = "arbitrary")]
4947 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4948 use arbitrary::{Arbitrary, Unstructured};
4949 let mut buf = [0u8; 1024];
4950 rng.fill_bytes(&mut buf);
4951 let mut unstructured = Unstructured::new(&buf);
4952 Self::arbitrary(&mut unstructured).unwrap_or_default()
4953 }
4954}
4955impl Default for MISSION_WRITE_PARTIAL_LIST_DATA {
4956 fn default() -> Self {
4957 Self::DEFAULT.clone()
4958 }
4959}
4960impl MessageData for MISSION_WRITE_PARTIAL_LIST_DATA {
4961 type Message = MavMessage;
4962 const ID: u32 = 38u32;
4963 const NAME: &'static str = "MISSION_WRITE_PARTIAL_LIST";
4964 const EXTRA_CRC: u8 = 9u8;
4965 const ENCODED_LEN: usize = 7usize;
4966 fn deser(
4967 _version: MavlinkVersion,
4968 __input: &[u8],
4969 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4970 let avail_len = __input.len();
4971 let mut payload_buf = [0; Self::ENCODED_LEN];
4972 let mut buf = if avail_len < Self::ENCODED_LEN {
4973 payload_buf[0..avail_len].copy_from_slice(__input);
4974 Bytes::new(&payload_buf)
4975 } else {
4976 Bytes::new(__input)
4977 };
4978 let mut __struct = Self::default();
4979 __struct.start_index = buf.get_i16_le();
4980 __struct.end_index = buf.get_i16_le();
4981 __struct.target_system = buf.get_u8();
4982 __struct.target_component = buf.get_u8();
4983 let tmp = buf.get_u8();
4984 __struct.mission_type =
4985 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
4986 enum_type: "MavMissionType",
4987 value: tmp as u32,
4988 })?;
4989 Ok(__struct)
4990 }
4991 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4992 let mut __tmp = BytesMut::new(bytes);
4993 #[allow(clippy::absurd_extreme_comparisons)]
4994 #[allow(unused_comparisons)]
4995 if __tmp.remaining() < Self::ENCODED_LEN {
4996 panic!(
4997 "buffer is too small (need {} bytes, but got {})",
4998 Self::ENCODED_LEN,
4999 __tmp.remaining(),
5000 )
5001 }
5002 __tmp.put_i16_le(self.start_index);
5003 __tmp.put_i16_le(self.end_index);
5004 __tmp.put_u8(self.target_system);
5005 __tmp.put_u8(self.target_component);
5006 __tmp.put_u8(self.mission_type as u8);
5007 if matches!(version, MavlinkVersion::V2) {
5008 let len = __tmp.len();
5009 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5010 } else {
5011 __tmp.len()
5012 }
5013 }
5014}
5015#[doc = "id: 29"]
5016#[doc = "The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field."]
5017#[derive(Debug, Clone, PartialEq)]
5018#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5019#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5020pub struct SCALED_PRESSURE_DATA {
5021 #[doc = "Timestamp (time since system boot)."]
5022 pub time_boot_ms: u32,
5023 #[doc = "Absolute pressure"]
5024 pub press_abs: f32,
5025 #[doc = "Differential pressure 1"]
5026 pub press_diff: f32,
5027 #[doc = "Absolute pressure temperature"]
5028 pub temperature: i16,
5029 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
5030 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5031 pub temperature_press_diff: i16,
5032}
5033impl SCALED_PRESSURE_DATA {
5034 pub const ENCODED_LEN: usize = 16usize;
5035 pub const DEFAULT: Self = Self {
5036 time_boot_ms: 0_u32,
5037 press_abs: 0.0_f32,
5038 press_diff: 0.0_f32,
5039 temperature: 0_i16,
5040 temperature_press_diff: 0_i16,
5041 };
5042 #[cfg(feature = "arbitrary")]
5043 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5044 use arbitrary::{Arbitrary, Unstructured};
5045 let mut buf = [0u8; 1024];
5046 rng.fill_bytes(&mut buf);
5047 let mut unstructured = Unstructured::new(&buf);
5048 Self::arbitrary(&mut unstructured).unwrap_or_default()
5049 }
5050}
5051impl Default for SCALED_PRESSURE_DATA {
5052 fn default() -> Self {
5053 Self::DEFAULT.clone()
5054 }
5055}
5056impl MessageData for SCALED_PRESSURE_DATA {
5057 type Message = MavMessage;
5058 const ID: u32 = 29u32;
5059 const NAME: &'static str = "SCALED_PRESSURE";
5060 const EXTRA_CRC: u8 = 115u8;
5061 const ENCODED_LEN: usize = 16usize;
5062 fn deser(
5063 _version: MavlinkVersion,
5064 __input: &[u8],
5065 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5066 let avail_len = __input.len();
5067 let mut payload_buf = [0; Self::ENCODED_LEN];
5068 let mut buf = if avail_len < Self::ENCODED_LEN {
5069 payload_buf[0..avail_len].copy_from_slice(__input);
5070 Bytes::new(&payload_buf)
5071 } else {
5072 Bytes::new(__input)
5073 };
5074 let mut __struct = Self::default();
5075 __struct.time_boot_ms = buf.get_u32_le();
5076 __struct.press_abs = buf.get_f32_le();
5077 __struct.press_diff = buf.get_f32_le();
5078 __struct.temperature = buf.get_i16_le();
5079 __struct.temperature_press_diff = buf.get_i16_le();
5080 Ok(__struct)
5081 }
5082 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5083 let mut __tmp = BytesMut::new(bytes);
5084 #[allow(clippy::absurd_extreme_comparisons)]
5085 #[allow(unused_comparisons)]
5086 if __tmp.remaining() < Self::ENCODED_LEN {
5087 panic!(
5088 "buffer is too small (need {} bytes, but got {})",
5089 Self::ENCODED_LEN,
5090 __tmp.remaining(),
5091 )
5092 }
5093 __tmp.put_u32_le(self.time_boot_ms);
5094 __tmp.put_f32_le(self.press_abs);
5095 __tmp.put_f32_le(self.press_diff);
5096 __tmp.put_i16_le(self.temperature);
5097 __tmp.put_i16_le(self.temperature_press_diff);
5098 if matches!(version, MavlinkVersion::V2) {
5099 let len = __tmp.len();
5100 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5101 } else {
5102 __tmp.len()
5103 }
5104 }
5105}
5106#[doc = "id: 333"]
5107#[doc = "Describe a trajectory using an array of up-to 5 bezier control points in the local frame (MAV_FRAME_LOCAL_NED)."]
5108#[derive(Debug, Clone, PartialEq)]
5109#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5110#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5111pub struct TRAJECTORY_REPRESENTATION_BEZIER_DATA {
5112 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
5113 pub time_usec: u64,
5114 #[doc = "X-coordinate of bezier control points. Set to NaN if not being used"]
5115 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5116 pub pos_x: [f32; 5],
5117 #[doc = "Y-coordinate of bezier control points. Set to NaN if not being used"]
5118 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5119 pub pos_y: [f32; 5],
5120 #[doc = "Z-coordinate of bezier control points. Set to NaN if not being used"]
5121 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5122 pub pos_z: [f32; 5],
5123 #[doc = "Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated"]
5124 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5125 pub delta: [f32; 5],
5126 #[doc = "Yaw. Set to NaN for unchanged"]
5127 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5128 pub pos_yaw: [f32; 5],
5129 #[doc = "Number of valid control points (up-to 5 points are possible)"]
5130 pub valid_points: u8,
5131}
5132impl TRAJECTORY_REPRESENTATION_BEZIER_DATA {
5133 pub const ENCODED_LEN: usize = 109usize;
5134 pub const DEFAULT: Self = Self {
5135 time_usec: 0_u64,
5136 pos_x: [0.0_f32; 5usize],
5137 pos_y: [0.0_f32; 5usize],
5138 pos_z: [0.0_f32; 5usize],
5139 delta: [0.0_f32; 5usize],
5140 pos_yaw: [0.0_f32; 5usize],
5141 valid_points: 0_u8,
5142 };
5143 #[cfg(feature = "arbitrary")]
5144 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5145 use arbitrary::{Arbitrary, Unstructured};
5146 let mut buf = [0u8; 1024];
5147 rng.fill_bytes(&mut buf);
5148 let mut unstructured = Unstructured::new(&buf);
5149 Self::arbitrary(&mut unstructured).unwrap_or_default()
5150 }
5151}
5152impl Default for TRAJECTORY_REPRESENTATION_BEZIER_DATA {
5153 fn default() -> Self {
5154 Self::DEFAULT.clone()
5155 }
5156}
5157impl MessageData for TRAJECTORY_REPRESENTATION_BEZIER_DATA {
5158 type Message = MavMessage;
5159 const ID: u32 = 333u32;
5160 const NAME: &'static str = "TRAJECTORY_REPRESENTATION_BEZIER";
5161 const EXTRA_CRC: u8 = 231u8;
5162 const ENCODED_LEN: usize = 109usize;
5163 fn deser(
5164 _version: MavlinkVersion,
5165 __input: &[u8],
5166 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5167 let avail_len = __input.len();
5168 let mut payload_buf = [0; Self::ENCODED_LEN];
5169 let mut buf = if avail_len < Self::ENCODED_LEN {
5170 payload_buf[0..avail_len].copy_from_slice(__input);
5171 Bytes::new(&payload_buf)
5172 } else {
5173 Bytes::new(__input)
5174 };
5175 let mut __struct = Self::default();
5176 __struct.time_usec = buf.get_u64_le();
5177 for v in &mut __struct.pos_x {
5178 let val = buf.get_f32_le();
5179 *v = val;
5180 }
5181 for v in &mut __struct.pos_y {
5182 let val = buf.get_f32_le();
5183 *v = val;
5184 }
5185 for v in &mut __struct.pos_z {
5186 let val = buf.get_f32_le();
5187 *v = val;
5188 }
5189 for v in &mut __struct.delta {
5190 let val = buf.get_f32_le();
5191 *v = val;
5192 }
5193 for v in &mut __struct.pos_yaw {
5194 let val = buf.get_f32_le();
5195 *v = val;
5196 }
5197 __struct.valid_points = buf.get_u8();
5198 Ok(__struct)
5199 }
5200 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5201 let mut __tmp = BytesMut::new(bytes);
5202 #[allow(clippy::absurd_extreme_comparisons)]
5203 #[allow(unused_comparisons)]
5204 if __tmp.remaining() < Self::ENCODED_LEN {
5205 panic!(
5206 "buffer is too small (need {} bytes, but got {})",
5207 Self::ENCODED_LEN,
5208 __tmp.remaining(),
5209 )
5210 }
5211 __tmp.put_u64_le(self.time_usec);
5212 for val in &self.pos_x {
5213 __tmp.put_f32_le(*val);
5214 }
5215 for val in &self.pos_y {
5216 __tmp.put_f32_le(*val);
5217 }
5218 for val in &self.pos_z {
5219 __tmp.put_f32_le(*val);
5220 }
5221 for val in &self.delta {
5222 __tmp.put_f32_le(*val);
5223 }
5224 for val in &self.pos_yaw {
5225 __tmp.put_f32_le(*val);
5226 }
5227 __tmp.put_u8(self.valid_points);
5228 if matches!(version, MavlinkVersion::V2) {
5229 let len = __tmp.len();
5230 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5231 } else {
5232 __tmp.len()
5233 }
5234 }
5235}
5236#[doc = "id: 360"]
5237#[doc = "Vehicle status report that is sent out while orbit execution is in progress (see MAV_CMD_DO_ORBIT)."]
5238#[derive(Debug, Clone, PartialEq)]
5239#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5240#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5241pub struct ORBIT_EXECUTION_STATUS_DATA {
5242 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
5243 pub time_usec: u64,
5244 #[doc = "Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise."]
5245 pub radius: f32,
5246 #[doc = "X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7."]
5247 pub x: i32,
5248 #[doc = "Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7."]
5249 pub y: i32,
5250 #[doc = "Altitude of center point. Coordinate system depends on frame field."]
5251 pub z: f32,
5252 #[doc = "The coordinate system of the fields: x, y, z."]
5253 pub frame: MavFrame,
5254}
5255impl ORBIT_EXECUTION_STATUS_DATA {
5256 pub const ENCODED_LEN: usize = 25usize;
5257 pub const DEFAULT: Self = Self {
5258 time_usec: 0_u64,
5259 radius: 0.0_f32,
5260 x: 0_i32,
5261 y: 0_i32,
5262 z: 0.0_f32,
5263 frame: MavFrame::DEFAULT,
5264 };
5265 #[cfg(feature = "arbitrary")]
5266 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5267 use arbitrary::{Arbitrary, Unstructured};
5268 let mut buf = [0u8; 1024];
5269 rng.fill_bytes(&mut buf);
5270 let mut unstructured = Unstructured::new(&buf);
5271 Self::arbitrary(&mut unstructured).unwrap_or_default()
5272 }
5273}
5274impl Default for ORBIT_EXECUTION_STATUS_DATA {
5275 fn default() -> Self {
5276 Self::DEFAULT.clone()
5277 }
5278}
5279impl MessageData for ORBIT_EXECUTION_STATUS_DATA {
5280 type Message = MavMessage;
5281 const ID: u32 = 360u32;
5282 const NAME: &'static str = "ORBIT_EXECUTION_STATUS";
5283 const EXTRA_CRC: u8 = 11u8;
5284 const ENCODED_LEN: usize = 25usize;
5285 fn deser(
5286 _version: MavlinkVersion,
5287 __input: &[u8],
5288 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5289 let avail_len = __input.len();
5290 let mut payload_buf = [0; Self::ENCODED_LEN];
5291 let mut buf = if avail_len < Self::ENCODED_LEN {
5292 payload_buf[0..avail_len].copy_from_slice(__input);
5293 Bytes::new(&payload_buf)
5294 } else {
5295 Bytes::new(__input)
5296 };
5297 let mut __struct = Self::default();
5298 __struct.time_usec = buf.get_u64_le();
5299 __struct.radius = buf.get_f32_le();
5300 __struct.x = buf.get_i32_le();
5301 __struct.y = buf.get_i32_le();
5302 __struct.z = buf.get_f32_le();
5303 let tmp = buf.get_u8();
5304 __struct.frame =
5305 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
5306 enum_type: "MavFrame",
5307 value: tmp as u32,
5308 })?;
5309 Ok(__struct)
5310 }
5311 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5312 let mut __tmp = BytesMut::new(bytes);
5313 #[allow(clippy::absurd_extreme_comparisons)]
5314 #[allow(unused_comparisons)]
5315 if __tmp.remaining() < Self::ENCODED_LEN {
5316 panic!(
5317 "buffer is too small (need {} bytes, but got {})",
5318 Self::ENCODED_LEN,
5319 __tmp.remaining(),
5320 )
5321 }
5322 __tmp.put_u64_le(self.time_usec);
5323 __tmp.put_f32_le(self.radius);
5324 __tmp.put_i32_le(self.x);
5325 __tmp.put_i32_le(self.y);
5326 __tmp.put_f32_le(self.z);
5327 __tmp.put_u8(self.frame as u8);
5328 if matches!(version, MavlinkVersion::V2) {
5329 let len = __tmp.len();
5330 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5331 } else {
5332 __tmp.len()
5333 }
5334 }
5335}
5336#[doc = "id: 7"]
5337#[doc = "Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety."]
5338#[derive(Debug, Clone, PartialEq)]
5339#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5340#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5341pub struct AUTH_KEY_DATA {
5342 #[doc = "key"]
5343 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5344 pub key: [u8; 32],
5345}
5346impl AUTH_KEY_DATA {
5347 pub const ENCODED_LEN: usize = 32usize;
5348 pub const DEFAULT: Self = Self {
5349 key: [0_u8; 32usize],
5350 };
5351 #[cfg(feature = "arbitrary")]
5352 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5353 use arbitrary::{Arbitrary, Unstructured};
5354 let mut buf = [0u8; 1024];
5355 rng.fill_bytes(&mut buf);
5356 let mut unstructured = Unstructured::new(&buf);
5357 Self::arbitrary(&mut unstructured).unwrap_or_default()
5358 }
5359}
5360impl Default for AUTH_KEY_DATA {
5361 fn default() -> Self {
5362 Self::DEFAULT.clone()
5363 }
5364}
5365impl MessageData for AUTH_KEY_DATA {
5366 type Message = MavMessage;
5367 const ID: u32 = 7u32;
5368 const NAME: &'static str = "AUTH_KEY";
5369 const EXTRA_CRC: u8 = 119u8;
5370 const ENCODED_LEN: usize = 32usize;
5371 fn deser(
5372 _version: MavlinkVersion,
5373 __input: &[u8],
5374 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5375 let avail_len = __input.len();
5376 let mut payload_buf = [0; Self::ENCODED_LEN];
5377 let mut buf = if avail_len < Self::ENCODED_LEN {
5378 payload_buf[0..avail_len].copy_from_slice(__input);
5379 Bytes::new(&payload_buf)
5380 } else {
5381 Bytes::new(__input)
5382 };
5383 let mut __struct = Self::default();
5384 for v in &mut __struct.key {
5385 let val = buf.get_u8();
5386 *v = val;
5387 }
5388 Ok(__struct)
5389 }
5390 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5391 let mut __tmp = BytesMut::new(bytes);
5392 #[allow(clippy::absurd_extreme_comparisons)]
5393 #[allow(unused_comparisons)]
5394 if __tmp.remaining() < Self::ENCODED_LEN {
5395 panic!(
5396 "buffer is too small (need {} bytes, but got {})",
5397 Self::ENCODED_LEN,
5398 __tmp.remaining(),
5399 )
5400 }
5401 for val in &self.key {
5402 __tmp.put_u8(*val);
5403 }
5404 if matches!(version, MavlinkVersion::V2) {
5405 let len = __tmp.len();
5406 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5407 } else {
5408 __tmp.len()
5409 }
5410 }
5411}
5412#[doc = "id: 110"]
5413#[doc = "File transfer protocol message: <https://mavlink.io/en/services/ftp.html>."]
5414#[derive(Debug, Clone, PartialEq)]
5415#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5416#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5417pub struct FILE_TRANSFER_PROTOCOL_DATA {
5418 #[doc = "Network ID (0 for broadcast)"]
5419 pub target_network: u8,
5420 #[doc = "System ID (0 for broadcast)"]
5421 pub target_system: u8,
5422 #[doc = "Component ID (0 for broadcast)"]
5423 pub target_component: u8,
5424 #[doc = "Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in <https://mavlink.io/en/services/ftp.html>."]
5425 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5426 pub payload: [u8; 251],
5427}
5428impl FILE_TRANSFER_PROTOCOL_DATA {
5429 pub const ENCODED_LEN: usize = 254usize;
5430 pub const DEFAULT: Self = Self {
5431 target_network: 0_u8,
5432 target_system: 0_u8,
5433 target_component: 0_u8,
5434 payload: [0_u8; 251usize],
5435 };
5436 #[cfg(feature = "arbitrary")]
5437 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5438 use arbitrary::{Arbitrary, Unstructured};
5439 let mut buf = [0u8; 1024];
5440 rng.fill_bytes(&mut buf);
5441 let mut unstructured = Unstructured::new(&buf);
5442 Self::arbitrary(&mut unstructured).unwrap_or_default()
5443 }
5444}
5445impl Default for FILE_TRANSFER_PROTOCOL_DATA {
5446 fn default() -> Self {
5447 Self::DEFAULT.clone()
5448 }
5449}
5450impl MessageData for FILE_TRANSFER_PROTOCOL_DATA {
5451 type Message = MavMessage;
5452 const ID: u32 = 110u32;
5453 const NAME: &'static str = "FILE_TRANSFER_PROTOCOL";
5454 const EXTRA_CRC: u8 = 84u8;
5455 const ENCODED_LEN: usize = 254usize;
5456 fn deser(
5457 _version: MavlinkVersion,
5458 __input: &[u8],
5459 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5460 let avail_len = __input.len();
5461 let mut payload_buf = [0; Self::ENCODED_LEN];
5462 let mut buf = if avail_len < Self::ENCODED_LEN {
5463 payload_buf[0..avail_len].copy_from_slice(__input);
5464 Bytes::new(&payload_buf)
5465 } else {
5466 Bytes::new(__input)
5467 };
5468 let mut __struct = Self::default();
5469 __struct.target_network = buf.get_u8();
5470 __struct.target_system = buf.get_u8();
5471 __struct.target_component = buf.get_u8();
5472 for v in &mut __struct.payload {
5473 let val = buf.get_u8();
5474 *v = val;
5475 }
5476 Ok(__struct)
5477 }
5478 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5479 let mut __tmp = BytesMut::new(bytes);
5480 #[allow(clippy::absurd_extreme_comparisons)]
5481 #[allow(unused_comparisons)]
5482 if __tmp.remaining() < Self::ENCODED_LEN {
5483 panic!(
5484 "buffer is too small (need {} bytes, but got {})",
5485 Self::ENCODED_LEN,
5486 __tmp.remaining(),
5487 )
5488 }
5489 __tmp.put_u8(self.target_network);
5490 __tmp.put_u8(self.target_system);
5491 __tmp.put_u8(self.target_component);
5492 for val in &self.payload {
5493 __tmp.put_u8(*val);
5494 }
5495 if matches!(version, MavlinkVersion::V2) {
5496 let len = __tmp.len();
5497 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5498 } else {
5499 __tmp.len()
5500 }
5501 }
5502}
5503#[doc = "id: 1"]
5504#[doc = "The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout."]
5505#[derive(Debug, Clone, PartialEq)]
5506#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5507#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5508pub struct SYS_STATUS_DATA {
5509 #[doc = "Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present."]
5510 pub onboard_control_sensors_present: MavSysStatusSensor,
5511 #[doc = "Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled."]
5512 pub onboard_control_sensors_enabled: MavSysStatusSensor,
5513 #[doc = "Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy."]
5514 pub onboard_control_sensors_health: MavSysStatusSensor,
5515 #[doc = "Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000"]
5516 pub load: u16,
5517 #[doc = "Battery voltage, UINT16_MAX: Voltage not sent by autopilot"]
5518 pub voltage_battery: u16,
5519 #[doc = "Battery current, -1: Current not sent by autopilot"]
5520 pub current_battery: i16,
5521 #[doc = "Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)"]
5522 pub drop_rate_comm: u16,
5523 #[doc = "Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)"]
5524 pub errors_comm: u16,
5525 #[doc = "Autopilot-specific errors"]
5526 pub errors_count1: u16,
5527 #[doc = "Autopilot-specific errors"]
5528 pub errors_count2: u16,
5529 #[doc = "Autopilot-specific errors"]
5530 pub errors_count3: u16,
5531 #[doc = "Autopilot-specific errors"]
5532 pub errors_count4: u16,
5533 #[doc = "Battery energy remaining, -1: Battery remaining energy not sent by autopilot"]
5534 pub battery_remaining: i8,
5535 #[doc = "Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present."]
5536 #[cfg_attr(feature = "serde", serde(default))]
5537 pub onboard_control_sensors_present_extended: MavSysStatusSensorExtended,
5538 #[doc = "Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled."]
5539 #[cfg_attr(feature = "serde", serde(default))]
5540 pub onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended,
5541 #[doc = "Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy."]
5542 #[cfg_attr(feature = "serde", serde(default))]
5543 pub onboard_control_sensors_health_extended: MavSysStatusSensorExtended,
5544}
5545impl SYS_STATUS_DATA {
5546 pub const ENCODED_LEN: usize = 43usize;
5547 pub const DEFAULT: Self = Self {
5548 onboard_control_sensors_present: MavSysStatusSensor::DEFAULT,
5549 onboard_control_sensors_enabled: MavSysStatusSensor::DEFAULT,
5550 onboard_control_sensors_health: MavSysStatusSensor::DEFAULT,
5551 load: 0_u16,
5552 voltage_battery: 0_u16,
5553 current_battery: 0_i16,
5554 drop_rate_comm: 0_u16,
5555 errors_comm: 0_u16,
5556 errors_count1: 0_u16,
5557 errors_count2: 0_u16,
5558 errors_count3: 0_u16,
5559 errors_count4: 0_u16,
5560 battery_remaining: 0_i8,
5561 onboard_control_sensors_present_extended: MavSysStatusSensorExtended::DEFAULT,
5562 onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended::DEFAULT,
5563 onboard_control_sensors_health_extended: MavSysStatusSensorExtended::DEFAULT,
5564 };
5565 #[cfg(feature = "arbitrary")]
5566 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5567 use arbitrary::{Arbitrary, Unstructured};
5568 let mut buf = [0u8; 1024];
5569 rng.fill_bytes(&mut buf);
5570 let mut unstructured = Unstructured::new(&buf);
5571 Self::arbitrary(&mut unstructured).unwrap_or_default()
5572 }
5573}
5574impl Default for SYS_STATUS_DATA {
5575 fn default() -> Self {
5576 Self::DEFAULT.clone()
5577 }
5578}
5579impl MessageData for SYS_STATUS_DATA {
5580 type Message = MavMessage;
5581 const ID: u32 = 1u32;
5582 const NAME: &'static str = "SYS_STATUS";
5583 const EXTRA_CRC: u8 = 124u8;
5584 const ENCODED_LEN: usize = 43usize;
5585 fn deser(
5586 _version: MavlinkVersion,
5587 __input: &[u8],
5588 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5589 let avail_len = __input.len();
5590 let mut payload_buf = [0; Self::ENCODED_LEN];
5591 let mut buf = if avail_len < Self::ENCODED_LEN {
5592 payload_buf[0..avail_len].copy_from_slice(__input);
5593 Bytes::new(&payload_buf)
5594 } else {
5595 Bytes::new(__input)
5596 };
5597 let mut __struct = Self::default();
5598 let tmp = buf.get_u32_le();
5599 __struct.onboard_control_sensors_present = MavSysStatusSensor::from_bits(
5600 tmp & MavSysStatusSensor::all().bits(),
5601 )
5602 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
5603 flag_type: "MavSysStatusSensor",
5604 value: tmp as u32,
5605 })?;
5606 let tmp = buf.get_u32_le();
5607 __struct.onboard_control_sensors_enabled = MavSysStatusSensor::from_bits(
5608 tmp & MavSysStatusSensor::all().bits(),
5609 )
5610 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
5611 flag_type: "MavSysStatusSensor",
5612 value: tmp as u32,
5613 })?;
5614 let tmp = buf.get_u32_le();
5615 __struct.onboard_control_sensors_health = MavSysStatusSensor::from_bits(
5616 tmp & MavSysStatusSensor::all().bits(),
5617 )
5618 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
5619 flag_type: "MavSysStatusSensor",
5620 value: tmp as u32,
5621 })?;
5622 __struct.load = buf.get_u16_le();
5623 __struct.voltage_battery = buf.get_u16_le();
5624 __struct.current_battery = buf.get_i16_le();
5625 __struct.drop_rate_comm = buf.get_u16_le();
5626 __struct.errors_comm = buf.get_u16_le();
5627 __struct.errors_count1 = buf.get_u16_le();
5628 __struct.errors_count2 = buf.get_u16_le();
5629 __struct.errors_count3 = buf.get_u16_le();
5630 __struct.errors_count4 = buf.get_u16_le();
5631 __struct.battery_remaining = buf.get_i8();
5632 let tmp = buf.get_u32_le();
5633 __struct.onboard_control_sensors_present_extended =
5634 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
5635 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
5636 flag_type: "MavSysStatusSensorExtended",
5637 value: tmp as u32,
5638 })?;
5639 let tmp = buf.get_u32_le();
5640 __struct.onboard_control_sensors_enabled_extended =
5641 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
5642 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
5643 flag_type: "MavSysStatusSensorExtended",
5644 value: tmp as u32,
5645 })?;
5646 let tmp = buf.get_u32_le();
5647 __struct.onboard_control_sensors_health_extended =
5648 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
5649 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
5650 flag_type: "MavSysStatusSensorExtended",
5651 value: tmp as u32,
5652 })?;
5653 Ok(__struct)
5654 }
5655 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5656 let mut __tmp = BytesMut::new(bytes);
5657 #[allow(clippy::absurd_extreme_comparisons)]
5658 #[allow(unused_comparisons)]
5659 if __tmp.remaining() < Self::ENCODED_LEN {
5660 panic!(
5661 "buffer is too small (need {} bytes, but got {})",
5662 Self::ENCODED_LEN,
5663 __tmp.remaining(),
5664 )
5665 }
5666 __tmp.put_u32_le(self.onboard_control_sensors_present.bits());
5667 __tmp.put_u32_le(self.onboard_control_sensors_enabled.bits());
5668 __tmp.put_u32_le(self.onboard_control_sensors_health.bits());
5669 __tmp.put_u16_le(self.load);
5670 __tmp.put_u16_le(self.voltage_battery);
5671 __tmp.put_i16_le(self.current_battery);
5672 __tmp.put_u16_le(self.drop_rate_comm);
5673 __tmp.put_u16_le(self.errors_comm);
5674 __tmp.put_u16_le(self.errors_count1);
5675 __tmp.put_u16_le(self.errors_count2);
5676 __tmp.put_u16_le(self.errors_count3);
5677 __tmp.put_u16_le(self.errors_count4);
5678 __tmp.put_i8(self.battery_remaining);
5679 __tmp.put_u32_le(self.onboard_control_sensors_present_extended.bits());
5680 __tmp.put_u32_le(self.onboard_control_sensors_enabled_extended.bits());
5681 __tmp.put_u32_le(self.onboard_control_sensors_health_extended.bits());
5682 if matches!(version, MavlinkVersion::V2) {
5683 let len = __tmp.len();
5684 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5685 } else {
5686 __tmp.len()
5687 }
5688 }
5689}
5690#[doc = "id: 122"]
5691#[doc = "Stop log transfer and resume normal logging."]
5692#[derive(Debug, Clone, PartialEq)]
5693#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5694#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5695pub struct LOG_REQUEST_END_DATA {
5696 #[doc = "System ID"]
5697 pub target_system: u8,
5698 #[doc = "Component ID"]
5699 pub target_component: u8,
5700}
5701impl LOG_REQUEST_END_DATA {
5702 pub const ENCODED_LEN: usize = 2usize;
5703 pub const DEFAULT: Self = Self {
5704 target_system: 0_u8,
5705 target_component: 0_u8,
5706 };
5707 #[cfg(feature = "arbitrary")]
5708 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5709 use arbitrary::{Arbitrary, Unstructured};
5710 let mut buf = [0u8; 1024];
5711 rng.fill_bytes(&mut buf);
5712 let mut unstructured = Unstructured::new(&buf);
5713 Self::arbitrary(&mut unstructured).unwrap_or_default()
5714 }
5715}
5716impl Default for LOG_REQUEST_END_DATA {
5717 fn default() -> Self {
5718 Self::DEFAULT.clone()
5719 }
5720}
5721impl MessageData for LOG_REQUEST_END_DATA {
5722 type Message = MavMessage;
5723 const ID: u32 = 122u32;
5724 const NAME: &'static str = "LOG_REQUEST_END";
5725 const EXTRA_CRC: u8 = 203u8;
5726 const ENCODED_LEN: usize = 2usize;
5727 fn deser(
5728 _version: MavlinkVersion,
5729 __input: &[u8],
5730 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5731 let avail_len = __input.len();
5732 let mut payload_buf = [0; Self::ENCODED_LEN];
5733 let mut buf = if avail_len < Self::ENCODED_LEN {
5734 payload_buf[0..avail_len].copy_from_slice(__input);
5735 Bytes::new(&payload_buf)
5736 } else {
5737 Bytes::new(__input)
5738 };
5739 let mut __struct = Self::default();
5740 __struct.target_system = buf.get_u8();
5741 __struct.target_component = buf.get_u8();
5742 Ok(__struct)
5743 }
5744 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5745 let mut __tmp = BytesMut::new(bytes);
5746 #[allow(clippy::absurd_extreme_comparisons)]
5747 #[allow(unused_comparisons)]
5748 if __tmp.remaining() < Self::ENCODED_LEN {
5749 panic!(
5750 "buffer is too small (need {} bytes, but got {})",
5751 Self::ENCODED_LEN,
5752 __tmp.remaining(),
5753 )
5754 }
5755 __tmp.put_u8(self.target_system);
5756 __tmp.put_u8(self.target_component);
5757 if matches!(version, MavlinkVersion::V2) {
5758 let len = __tmp.len();
5759 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5760 } else {
5761 __tmp.len()
5762 }
5763 }
5764}
5765#[doc = "id: 134"]
5766#[doc = "Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
5767#[derive(Debug, Clone, PartialEq)]
5768#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5769#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5770pub struct TERRAIN_DATA_DATA {
5771 #[doc = "Latitude of SW corner of first grid"]
5772 pub lat: i32,
5773 #[doc = "Longitude of SW corner of first grid"]
5774 pub lon: i32,
5775 #[doc = "Grid spacing"]
5776 pub grid_spacing: u16,
5777 #[doc = "Terrain data MSL"]
5778 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5779 pub data: [i16; 16],
5780 #[doc = "bit within the terrain request mask"]
5781 pub gridbit: u8,
5782}
5783impl TERRAIN_DATA_DATA {
5784 pub const ENCODED_LEN: usize = 43usize;
5785 pub const DEFAULT: Self = Self {
5786 lat: 0_i32,
5787 lon: 0_i32,
5788 grid_spacing: 0_u16,
5789 data: [0_i16; 16usize],
5790 gridbit: 0_u8,
5791 };
5792 #[cfg(feature = "arbitrary")]
5793 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5794 use arbitrary::{Arbitrary, Unstructured};
5795 let mut buf = [0u8; 1024];
5796 rng.fill_bytes(&mut buf);
5797 let mut unstructured = Unstructured::new(&buf);
5798 Self::arbitrary(&mut unstructured).unwrap_or_default()
5799 }
5800}
5801impl Default for TERRAIN_DATA_DATA {
5802 fn default() -> Self {
5803 Self::DEFAULT.clone()
5804 }
5805}
5806impl MessageData for TERRAIN_DATA_DATA {
5807 type Message = MavMessage;
5808 const ID: u32 = 134u32;
5809 const NAME: &'static str = "TERRAIN_DATA";
5810 const EXTRA_CRC: u8 = 229u8;
5811 const ENCODED_LEN: usize = 43usize;
5812 fn deser(
5813 _version: MavlinkVersion,
5814 __input: &[u8],
5815 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5816 let avail_len = __input.len();
5817 let mut payload_buf = [0; Self::ENCODED_LEN];
5818 let mut buf = if avail_len < Self::ENCODED_LEN {
5819 payload_buf[0..avail_len].copy_from_slice(__input);
5820 Bytes::new(&payload_buf)
5821 } else {
5822 Bytes::new(__input)
5823 };
5824 let mut __struct = Self::default();
5825 __struct.lat = buf.get_i32_le();
5826 __struct.lon = buf.get_i32_le();
5827 __struct.grid_spacing = buf.get_u16_le();
5828 for v in &mut __struct.data {
5829 let val = buf.get_i16_le();
5830 *v = val;
5831 }
5832 __struct.gridbit = buf.get_u8();
5833 Ok(__struct)
5834 }
5835 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5836 let mut __tmp = BytesMut::new(bytes);
5837 #[allow(clippy::absurd_extreme_comparisons)]
5838 #[allow(unused_comparisons)]
5839 if __tmp.remaining() < Self::ENCODED_LEN {
5840 panic!(
5841 "buffer is too small (need {} bytes, but got {})",
5842 Self::ENCODED_LEN,
5843 __tmp.remaining(),
5844 )
5845 }
5846 __tmp.put_i32_le(self.lat);
5847 __tmp.put_i32_le(self.lon);
5848 __tmp.put_u16_le(self.grid_spacing);
5849 for val in &self.data {
5850 __tmp.put_i16_le(*val);
5851 }
5852 __tmp.put_u8(self.gridbit);
5853 if matches!(version, MavlinkVersion::V2) {
5854 let len = __tmp.len();
5855 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5856 } else {
5857 __tmp.len()
5858 }
5859 }
5860}
5861#[doc = "id: 267"]
5862#[doc = "A message containing logged data which requires a LOGGING_ACK to be sent back."]
5863#[derive(Debug, Clone, PartialEq)]
5864#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5865#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5866pub struct LOGGING_DATA_ACKED_DATA {
5867 #[doc = "sequence number (can wrap)"]
5868 pub sequence: u16,
5869 #[doc = "system ID of the target"]
5870 pub target_system: u8,
5871 #[doc = "component ID of the target"]
5872 pub target_component: u8,
5873 #[doc = "data length"]
5874 pub length: u8,
5875 #[doc = "offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists)."]
5876 pub first_message_offset: u8,
5877 #[doc = "logged data"]
5878 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5879 pub data: [u8; 249],
5880}
5881impl LOGGING_DATA_ACKED_DATA {
5882 pub const ENCODED_LEN: usize = 255usize;
5883 pub const DEFAULT: Self = Self {
5884 sequence: 0_u16,
5885 target_system: 0_u8,
5886 target_component: 0_u8,
5887 length: 0_u8,
5888 first_message_offset: 0_u8,
5889 data: [0_u8; 249usize],
5890 };
5891 #[cfg(feature = "arbitrary")]
5892 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5893 use arbitrary::{Arbitrary, Unstructured};
5894 let mut buf = [0u8; 1024];
5895 rng.fill_bytes(&mut buf);
5896 let mut unstructured = Unstructured::new(&buf);
5897 Self::arbitrary(&mut unstructured).unwrap_or_default()
5898 }
5899}
5900impl Default for LOGGING_DATA_ACKED_DATA {
5901 fn default() -> Self {
5902 Self::DEFAULT.clone()
5903 }
5904}
5905impl MessageData for LOGGING_DATA_ACKED_DATA {
5906 type Message = MavMessage;
5907 const ID: u32 = 267u32;
5908 const NAME: &'static str = "LOGGING_DATA_ACKED";
5909 const EXTRA_CRC: u8 = 35u8;
5910 const ENCODED_LEN: usize = 255usize;
5911 fn deser(
5912 _version: MavlinkVersion,
5913 __input: &[u8],
5914 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5915 let avail_len = __input.len();
5916 let mut payload_buf = [0; Self::ENCODED_LEN];
5917 let mut buf = if avail_len < Self::ENCODED_LEN {
5918 payload_buf[0..avail_len].copy_from_slice(__input);
5919 Bytes::new(&payload_buf)
5920 } else {
5921 Bytes::new(__input)
5922 };
5923 let mut __struct = Self::default();
5924 __struct.sequence = buf.get_u16_le();
5925 __struct.target_system = buf.get_u8();
5926 __struct.target_component = buf.get_u8();
5927 __struct.length = buf.get_u8();
5928 __struct.first_message_offset = buf.get_u8();
5929 for v in &mut __struct.data {
5930 let val = buf.get_u8();
5931 *v = val;
5932 }
5933 Ok(__struct)
5934 }
5935 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5936 let mut __tmp = BytesMut::new(bytes);
5937 #[allow(clippy::absurd_extreme_comparisons)]
5938 #[allow(unused_comparisons)]
5939 if __tmp.remaining() < Self::ENCODED_LEN {
5940 panic!(
5941 "buffer is too small (need {} bytes, but got {})",
5942 Self::ENCODED_LEN,
5943 __tmp.remaining(),
5944 )
5945 }
5946 __tmp.put_u16_le(self.sequence);
5947 __tmp.put_u8(self.target_system);
5948 __tmp.put_u8(self.target_component);
5949 __tmp.put_u8(self.length);
5950 __tmp.put_u8(self.first_message_offset);
5951 for val in &self.data {
5952 __tmp.put_u8(*val);
5953 }
5954 if matches!(version, MavlinkVersion::V2) {
5955 let len = __tmp.len();
5956 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5957 } else {
5958 __tmp.len()
5959 }
5960 }
5961}
5962#[doc = "id: 251"]
5963#[doc = "Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
5964#[derive(Debug, Clone, PartialEq)]
5965#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5966#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5967pub struct NAMED_VALUE_FLOAT_DATA {
5968 #[doc = "Timestamp (time since system boot)."]
5969 pub time_boot_ms: u32,
5970 #[doc = "Floating point value"]
5971 pub value: f32,
5972 #[doc = "Name of the debug variable"]
5973 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5974 pub name: [u8; 10],
5975}
5976impl NAMED_VALUE_FLOAT_DATA {
5977 pub const ENCODED_LEN: usize = 18usize;
5978 pub const DEFAULT: Self = Self {
5979 time_boot_ms: 0_u32,
5980 value: 0.0_f32,
5981 name: [0_u8; 10usize],
5982 };
5983 #[cfg(feature = "arbitrary")]
5984 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5985 use arbitrary::{Arbitrary, Unstructured};
5986 let mut buf = [0u8; 1024];
5987 rng.fill_bytes(&mut buf);
5988 let mut unstructured = Unstructured::new(&buf);
5989 Self::arbitrary(&mut unstructured).unwrap_or_default()
5990 }
5991}
5992impl Default for NAMED_VALUE_FLOAT_DATA {
5993 fn default() -> Self {
5994 Self::DEFAULT.clone()
5995 }
5996}
5997impl MessageData for NAMED_VALUE_FLOAT_DATA {
5998 type Message = MavMessage;
5999 const ID: u32 = 251u32;
6000 const NAME: &'static str = "NAMED_VALUE_FLOAT";
6001 const EXTRA_CRC: u8 = 170u8;
6002 const ENCODED_LEN: usize = 18usize;
6003 fn deser(
6004 _version: MavlinkVersion,
6005 __input: &[u8],
6006 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6007 let avail_len = __input.len();
6008 let mut payload_buf = [0; Self::ENCODED_LEN];
6009 let mut buf = if avail_len < Self::ENCODED_LEN {
6010 payload_buf[0..avail_len].copy_from_slice(__input);
6011 Bytes::new(&payload_buf)
6012 } else {
6013 Bytes::new(__input)
6014 };
6015 let mut __struct = Self::default();
6016 __struct.time_boot_ms = buf.get_u32_le();
6017 __struct.value = buf.get_f32_le();
6018 for v in &mut __struct.name {
6019 let val = buf.get_u8();
6020 *v = val;
6021 }
6022 Ok(__struct)
6023 }
6024 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6025 let mut __tmp = BytesMut::new(bytes);
6026 #[allow(clippy::absurd_extreme_comparisons)]
6027 #[allow(unused_comparisons)]
6028 if __tmp.remaining() < Self::ENCODED_LEN {
6029 panic!(
6030 "buffer is too small (need {} bytes, but got {})",
6031 Self::ENCODED_LEN,
6032 __tmp.remaining(),
6033 )
6034 }
6035 __tmp.put_u32_le(self.time_boot_ms);
6036 __tmp.put_f32_le(self.value);
6037 for val in &self.name {
6038 __tmp.put_u8(*val);
6039 }
6040 if matches!(version, MavlinkVersion::V2) {
6041 let len = __tmp.len();
6042 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6043 } else {
6044 __tmp.len()
6045 }
6046 }
6047}
6048#[doc = "id: 149"]
6049#[doc = "The location of a landing target. See: <https://mavlink.io/en/services/landing_target.html>."]
6050#[derive(Debug, Clone, PartialEq)]
6051#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6052#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6053pub struct LANDING_TARGET_DATA {
6054 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
6055 pub time_usec: u64,
6056 #[doc = "X-axis angular offset of the target from the center of the image"]
6057 pub angle_x: f32,
6058 #[doc = "Y-axis angular offset of the target from the center of the image"]
6059 pub angle_y: f32,
6060 #[doc = "Distance to the target from the vehicle"]
6061 pub distance: f32,
6062 #[doc = "Size of target along x-axis"]
6063 pub size_x: f32,
6064 #[doc = "Size of target along y-axis"]
6065 pub size_y: f32,
6066 #[doc = "The ID of the target if multiple targets are present"]
6067 pub target_num: u8,
6068 #[doc = "Coordinate frame used for following fields."]
6069 pub frame: MavFrame,
6070 #[doc = "X Position of the landing target in MAV_FRAME"]
6071 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6072 pub x: f32,
6073 #[doc = "Y Position of the landing target in MAV_FRAME"]
6074 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6075 pub y: f32,
6076 #[doc = "Z Position of the landing target in MAV_FRAME"]
6077 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6078 pub z: f32,
6079 #[doc = "Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
6080 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6081 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6082 pub q: [f32; 4],
6083 #[doc = "Type of landing target"]
6084 #[cfg_attr(feature = "serde", serde(default))]
6085 pub mavtype: LandingTargetType,
6086 #[doc = "Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid)."]
6087 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6088 pub position_valid: u8,
6089}
6090impl LANDING_TARGET_DATA {
6091 pub const ENCODED_LEN: usize = 60usize;
6092 pub const DEFAULT: Self = Self {
6093 time_usec: 0_u64,
6094 angle_x: 0.0_f32,
6095 angle_y: 0.0_f32,
6096 distance: 0.0_f32,
6097 size_x: 0.0_f32,
6098 size_y: 0.0_f32,
6099 target_num: 0_u8,
6100 frame: MavFrame::DEFAULT,
6101 x: 0.0_f32,
6102 y: 0.0_f32,
6103 z: 0.0_f32,
6104 q: [0.0_f32; 4usize],
6105 mavtype: LandingTargetType::DEFAULT,
6106 position_valid: 0_u8,
6107 };
6108 #[cfg(feature = "arbitrary")]
6109 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6110 use arbitrary::{Arbitrary, Unstructured};
6111 let mut buf = [0u8; 1024];
6112 rng.fill_bytes(&mut buf);
6113 let mut unstructured = Unstructured::new(&buf);
6114 Self::arbitrary(&mut unstructured).unwrap_or_default()
6115 }
6116}
6117impl Default for LANDING_TARGET_DATA {
6118 fn default() -> Self {
6119 Self::DEFAULT.clone()
6120 }
6121}
6122impl MessageData for LANDING_TARGET_DATA {
6123 type Message = MavMessage;
6124 const ID: u32 = 149u32;
6125 const NAME: &'static str = "LANDING_TARGET";
6126 const EXTRA_CRC: u8 = 200u8;
6127 const ENCODED_LEN: usize = 60usize;
6128 fn deser(
6129 _version: MavlinkVersion,
6130 __input: &[u8],
6131 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6132 let avail_len = __input.len();
6133 let mut payload_buf = [0; Self::ENCODED_LEN];
6134 let mut buf = if avail_len < Self::ENCODED_LEN {
6135 payload_buf[0..avail_len].copy_from_slice(__input);
6136 Bytes::new(&payload_buf)
6137 } else {
6138 Bytes::new(__input)
6139 };
6140 let mut __struct = Self::default();
6141 __struct.time_usec = buf.get_u64_le();
6142 __struct.angle_x = buf.get_f32_le();
6143 __struct.angle_y = buf.get_f32_le();
6144 __struct.distance = buf.get_f32_le();
6145 __struct.size_x = buf.get_f32_le();
6146 __struct.size_y = buf.get_f32_le();
6147 __struct.target_num = buf.get_u8();
6148 let tmp = buf.get_u8();
6149 __struct.frame =
6150 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6151 enum_type: "MavFrame",
6152 value: tmp as u32,
6153 })?;
6154 __struct.x = buf.get_f32_le();
6155 __struct.y = buf.get_f32_le();
6156 __struct.z = buf.get_f32_le();
6157 for v in &mut __struct.q {
6158 let val = buf.get_f32_le();
6159 *v = val;
6160 }
6161 let tmp = buf.get_u8();
6162 __struct.mavtype =
6163 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6164 enum_type: "LandingTargetType",
6165 value: tmp as u32,
6166 })?;
6167 __struct.position_valid = buf.get_u8();
6168 Ok(__struct)
6169 }
6170 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6171 let mut __tmp = BytesMut::new(bytes);
6172 #[allow(clippy::absurd_extreme_comparisons)]
6173 #[allow(unused_comparisons)]
6174 if __tmp.remaining() < Self::ENCODED_LEN {
6175 panic!(
6176 "buffer is too small (need {} bytes, but got {})",
6177 Self::ENCODED_LEN,
6178 __tmp.remaining(),
6179 )
6180 }
6181 __tmp.put_u64_le(self.time_usec);
6182 __tmp.put_f32_le(self.angle_x);
6183 __tmp.put_f32_le(self.angle_y);
6184 __tmp.put_f32_le(self.distance);
6185 __tmp.put_f32_le(self.size_x);
6186 __tmp.put_f32_le(self.size_y);
6187 __tmp.put_u8(self.target_num);
6188 __tmp.put_u8(self.frame as u8);
6189 __tmp.put_f32_le(self.x);
6190 __tmp.put_f32_le(self.y);
6191 __tmp.put_f32_le(self.z);
6192 for val in &self.q {
6193 __tmp.put_f32_le(*val);
6194 }
6195 __tmp.put_u8(self.mavtype as u8);
6196 __tmp.put_u8(self.position_valid);
6197 if matches!(version, MavlinkVersion::V2) {
6198 let len = __tmp.len();
6199 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6200 } else {
6201 __tmp.len()
6202 }
6203 }
6204}
6205#[doc = "id: 138"]
6206#[doc = "Motion capture attitude and position."]
6207#[derive(Debug, Clone, PartialEq)]
6208#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6209#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6210pub struct ATT_POS_MOCAP_DATA {
6211 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
6212 pub time_usec: u64,
6213 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
6214 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6215 pub q: [f32; 4],
6216 #[doc = "X position (NED)"]
6217 pub x: f32,
6218 #[doc = "Y position (NED)"]
6219 pub y: f32,
6220 #[doc = "Z position (NED)"]
6221 pub z: f32,
6222 #[doc = "Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
6223 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6224 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6225 pub covariance: [f32; 21],
6226}
6227impl ATT_POS_MOCAP_DATA {
6228 pub const ENCODED_LEN: usize = 120usize;
6229 pub const DEFAULT: Self = Self {
6230 time_usec: 0_u64,
6231 q: [0.0_f32; 4usize],
6232 x: 0.0_f32,
6233 y: 0.0_f32,
6234 z: 0.0_f32,
6235 covariance: [0.0_f32; 21usize],
6236 };
6237 #[cfg(feature = "arbitrary")]
6238 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6239 use arbitrary::{Arbitrary, Unstructured};
6240 let mut buf = [0u8; 1024];
6241 rng.fill_bytes(&mut buf);
6242 let mut unstructured = Unstructured::new(&buf);
6243 Self::arbitrary(&mut unstructured).unwrap_or_default()
6244 }
6245}
6246impl Default for ATT_POS_MOCAP_DATA {
6247 fn default() -> Self {
6248 Self::DEFAULT.clone()
6249 }
6250}
6251impl MessageData for ATT_POS_MOCAP_DATA {
6252 type Message = MavMessage;
6253 const ID: u32 = 138u32;
6254 const NAME: &'static str = "ATT_POS_MOCAP";
6255 const EXTRA_CRC: u8 = 109u8;
6256 const ENCODED_LEN: usize = 120usize;
6257 fn deser(
6258 _version: MavlinkVersion,
6259 __input: &[u8],
6260 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6261 let avail_len = __input.len();
6262 let mut payload_buf = [0; Self::ENCODED_LEN];
6263 let mut buf = if avail_len < Self::ENCODED_LEN {
6264 payload_buf[0..avail_len].copy_from_slice(__input);
6265 Bytes::new(&payload_buf)
6266 } else {
6267 Bytes::new(__input)
6268 };
6269 let mut __struct = Self::default();
6270 __struct.time_usec = buf.get_u64_le();
6271 for v in &mut __struct.q {
6272 let val = buf.get_f32_le();
6273 *v = val;
6274 }
6275 __struct.x = buf.get_f32_le();
6276 __struct.y = buf.get_f32_le();
6277 __struct.z = buf.get_f32_le();
6278 for v in &mut __struct.covariance {
6279 let val = buf.get_f32_le();
6280 *v = val;
6281 }
6282 Ok(__struct)
6283 }
6284 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6285 let mut __tmp = BytesMut::new(bytes);
6286 #[allow(clippy::absurd_extreme_comparisons)]
6287 #[allow(unused_comparisons)]
6288 if __tmp.remaining() < Self::ENCODED_LEN {
6289 panic!(
6290 "buffer is too small (need {} bytes, but got {})",
6291 Self::ENCODED_LEN,
6292 __tmp.remaining(),
6293 )
6294 }
6295 __tmp.put_u64_le(self.time_usec);
6296 for val in &self.q {
6297 __tmp.put_f32_le(*val);
6298 }
6299 __tmp.put_f32_le(self.x);
6300 __tmp.put_f32_le(self.y);
6301 __tmp.put_f32_le(self.z);
6302 for val in &self.covariance {
6303 __tmp.put_f32_le(*val);
6304 }
6305 if matches!(version, MavlinkVersion::V2) {
6306 let len = __tmp.len();
6307 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6308 } else {
6309 __tmp.len()
6310 }
6311 }
6312}
6313#[doc = "id: 129"]
6314#[doc = "The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units."]
6315#[derive(Debug, Clone, PartialEq)]
6316#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6317#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6318pub struct SCALED_IMU3_DATA {
6319 #[doc = "Timestamp (time since system boot)."]
6320 pub time_boot_ms: u32,
6321 #[doc = "X acceleration"]
6322 pub xacc: i16,
6323 #[doc = "Y acceleration"]
6324 pub yacc: i16,
6325 #[doc = "Z acceleration"]
6326 pub zacc: i16,
6327 #[doc = "Angular speed around X axis"]
6328 pub xgyro: i16,
6329 #[doc = "Angular speed around Y axis"]
6330 pub ygyro: i16,
6331 #[doc = "Angular speed around Z axis"]
6332 pub zgyro: i16,
6333 #[doc = "X Magnetic field"]
6334 pub xmag: i16,
6335 #[doc = "Y Magnetic field"]
6336 pub ymag: i16,
6337 #[doc = "Z Magnetic field"]
6338 pub zmag: i16,
6339 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
6340 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6341 pub temperature: i16,
6342}
6343impl SCALED_IMU3_DATA {
6344 pub const ENCODED_LEN: usize = 24usize;
6345 pub const DEFAULT: Self = Self {
6346 time_boot_ms: 0_u32,
6347 xacc: 0_i16,
6348 yacc: 0_i16,
6349 zacc: 0_i16,
6350 xgyro: 0_i16,
6351 ygyro: 0_i16,
6352 zgyro: 0_i16,
6353 xmag: 0_i16,
6354 ymag: 0_i16,
6355 zmag: 0_i16,
6356 temperature: 0_i16,
6357 };
6358 #[cfg(feature = "arbitrary")]
6359 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6360 use arbitrary::{Arbitrary, Unstructured};
6361 let mut buf = [0u8; 1024];
6362 rng.fill_bytes(&mut buf);
6363 let mut unstructured = Unstructured::new(&buf);
6364 Self::arbitrary(&mut unstructured).unwrap_or_default()
6365 }
6366}
6367impl Default for SCALED_IMU3_DATA {
6368 fn default() -> Self {
6369 Self::DEFAULT.clone()
6370 }
6371}
6372impl MessageData for SCALED_IMU3_DATA {
6373 type Message = MavMessage;
6374 const ID: u32 = 129u32;
6375 const NAME: &'static str = "SCALED_IMU3";
6376 const EXTRA_CRC: u8 = 46u8;
6377 const ENCODED_LEN: usize = 24usize;
6378 fn deser(
6379 _version: MavlinkVersion,
6380 __input: &[u8],
6381 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6382 let avail_len = __input.len();
6383 let mut payload_buf = [0; Self::ENCODED_LEN];
6384 let mut buf = if avail_len < Self::ENCODED_LEN {
6385 payload_buf[0..avail_len].copy_from_slice(__input);
6386 Bytes::new(&payload_buf)
6387 } else {
6388 Bytes::new(__input)
6389 };
6390 let mut __struct = Self::default();
6391 __struct.time_boot_ms = buf.get_u32_le();
6392 __struct.xacc = buf.get_i16_le();
6393 __struct.yacc = buf.get_i16_le();
6394 __struct.zacc = buf.get_i16_le();
6395 __struct.xgyro = buf.get_i16_le();
6396 __struct.ygyro = buf.get_i16_le();
6397 __struct.zgyro = buf.get_i16_le();
6398 __struct.xmag = buf.get_i16_le();
6399 __struct.ymag = buf.get_i16_le();
6400 __struct.zmag = buf.get_i16_le();
6401 __struct.temperature = buf.get_i16_le();
6402 Ok(__struct)
6403 }
6404 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6405 let mut __tmp = BytesMut::new(bytes);
6406 #[allow(clippy::absurd_extreme_comparisons)]
6407 #[allow(unused_comparisons)]
6408 if __tmp.remaining() < Self::ENCODED_LEN {
6409 panic!(
6410 "buffer is too small (need {} bytes, but got {})",
6411 Self::ENCODED_LEN,
6412 __tmp.remaining(),
6413 )
6414 }
6415 __tmp.put_u32_le(self.time_boot_ms);
6416 __tmp.put_i16_le(self.xacc);
6417 __tmp.put_i16_le(self.yacc);
6418 __tmp.put_i16_le(self.zacc);
6419 __tmp.put_i16_le(self.xgyro);
6420 __tmp.put_i16_le(self.ygyro);
6421 __tmp.put_i16_le(self.zgyro);
6422 __tmp.put_i16_le(self.xmag);
6423 __tmp.put_i16_le(self.ymag);
6424 __tmp.put_i16_le(self.zmag);
6425 __tmp.put_i16_le(self.temperature);
6426 if matches!(version, MavlinkVersion::V2) {
6427 let len = __tmp.len();
6428 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6429 } else {
6430 __tmp.len()
6431 }
6432 }
6433}
6434#[doc = "id: 249"]
6435#[doc = "Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
6436#[derive(Debug, Clone, PartialEq)]
6437#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6438#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6439pub struct MEMORY_VECT_DATA {
6440 #[doc = "Starting address of the debug variables"]
6441 pub address: u16,
6442 #[doc = "Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below"]
6443 pub ver: u8,
6444 #[doc = "Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14"]
6445 pub mavtype: u8,
6446 #[doc = "Memory contents at specified address"]
6447 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6448 pub value: [i8; 32],
6449}
6450impl MEMORY_VECT_DATA {
6451 pub const ENCODED_LEN: usize = 36usize;
6452 pub const DEFAULT: Self = Self {
6453 address: 0_u16,
6454 ver: 0_u8,
6455 mavtype: 0_u8,
6456 value: [0_i8; 32usize],
6457 };
6458 #[cfg(feature = "arbitrary")]
6459 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6460 use arbitrary::{Arbitrary, Unstructured};
6461 let mut buf = [0u8; 1024];
6462 rng.fill_bytes(&mut buf);
6463 let mut unstructured = Unstructured::new(&buf);
6464 Self::arbitrary(&mut unstructured).unwrap_or_default()
6465 }
6466}
6467impl Default for MEMORY_VECT_DATA {
6468 fn default() -> Self {
6469 Self::DEFAULT.clone()
6470 }
6471}
6472impl MessageData for MEMORY_VECT_DATA {
6473 type Message = MavMessage;
6474 const ID: u32 = 249u32;
6475 const NAME: &'static str = "MEMORY_VECT";
6476 const EXTRA_CRC: u8 = 204u8;
6477 const ENCODED_LEN: usize = 36usize;
6478 fn deser(
6479 _version: MavlinkVersion,
6480 __input: &[u8],
6481 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6482 let avail_len = __input.len();
6483 let mut payload_buf = [0; Self::ENCODED_LEN];
6484 let mut buf = if avail_len < Self::ENCODED_LEN {
6485 payload_buf[0..avail_len].copy_from_slice(__input);
6486 Bytes::new(&payload_buf)
6487 } else {
6488 Bytes::new(__input)
6489 };
6490 let mut __struct = Self::default();
6491 __struct.address = buf.get_u16_le();
6492 __struct.ver = buf.get_u8();
6493 __struct.mavtype = buf.get_u8();
6494 for v in &mut __struct.value {
6495 let val = buf.get_i8();
6496 *v = val;
6497 }
6498 Ok(__struct)
6499 }
6500 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6501 let mut __tmp = BytesMut::new(bytes);
6502 #[allow(clippy::absurd_extreme_comparisons)]
6503 #[allow(unused_comparisons)]
6504 if __tmp.remaining() < Self::ENCODED_LEN {
6505 panic!(
6506 "buffer is too small (need {} bytes, but got {})",
6507 Self::ENCODED_LEN,
6508 __tmp.remaining(),
6509 )
6510 }
6511 __tmp.put_u16_le(self.address);
6512 __tmp.put_u8(self.ver);
6513 __tmp.put_u8(self.mavtype);
6514 for val in &self.value {
6515 __tmp.put_i8(*val);
6516 }
6517 if matches!(version, MavlinkVersion::V2) {
6518 let len = __tmp.len();
6519 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6520 } else {
6521 __tmp.len()
6522 }
6523 }
6524}
6525#[doc = "id: 133"]
6526#[doc = "Request for terrain data and terrain status. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
6527#[derive(Debug, Clone, PartialEq)]
6528#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6529#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6530pub struct TERRAIN_REQUEST_DATA {
6531 #[doc = "Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)"]
6532 pub mask: u64,
6533 #[doc = "Latitude of SW corner of first grid"]
6534 pub lat: i32,
6535 #[doc = "Longitude of SW corner of first grid"]
6536 pub lon: i32,
6537 #[doc = "Grid spacing"]
6538 pub grid_spacing: u16,
6539}
6540impl TERRAIN_REQUEST_DATA {
6541 pub const ENCODED_LEN: usize = 18usize;
6542 pub const DEFAULT: Self = Self {
6543 mask: 0_u64,
6544 lat: 0_i32,
6545 lon: 0_i32,
6546 grid_spacing: 0_u16,
6547 };
6548 #[cfg(feature = "arbitrary")]
6549 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6550 use arbitrary::{Arbitrary, Unstructured};
6551 let mut buf = [0u8; 1024];
6552 rng.fill_bytes(&mut buf);
6553 let mut unstructured = Unstructured::new(&buf);
6554 Self::arbitrary(&mut unstructured).unwrap_or_default()
6555 }
6556}
6557impl Default for TERRAIN_REQUEST_DATA {
6558 fn default() -> Self {
6559 Self::DEFAULT.clone()
6560 }
6561}
6562impl MessageData for TERRAIN_REQUEST_DATA {
6563 type Message = MavMessage;
6564 const ID: u32 = 133u32;
6565 const NAME: &'static str = "TERRAIN_REQUEST";
6566 const EXTRA_CRC: u8 = 6u8;
6567 const ENCODED_LEN: usize = 18usize;
6568 fn deser(
6569 _version: MavlinkVersion,
6570 __input: &[u8],
6571 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6572 let avail_len = __input.len();
6573 let mut payload_buf = [0; Self::ENCODED_LEN];
6574 let mut buf = if avail_len < Self::ENCODED_LEN {
6575 payload_buf[0..avail_len].copy_from_slice(__input);
6576 Bytes::new(&payload_buf)
6577 } else {
6578 Bytes::new(__input)
6579 };
6580 let mut __struct = Self::default();
6581 __struct.mask = buf.get_u64_le();
6582 __struct.lat = buf.get_i32_le();
6583 __struct.lon = buf.get_i32_le();
6584 __struct.grid_spacing = buf.get_u16_le();
6585 Ok(__struct)
6586 }
6587 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6588 let mut __tmp = BytesMut::new(bytes);
6589 #[allow(clippy::absurd_extreme_comparisons)]
6590 #[allow(unused_comparisons)]
6591 if __tmp.remaining() < Self::ENCODED_LEN {
6592 panic!(
6593 "buffer is too small (need {} bytes, but got {})",
6594 Self::ENCODED_LEN,
6595 __tmp.remaining(),
6596 )
6597 }
6598 __tmp.put_u64_le(self.mask);
6599 __tmp.put_i32_le(self.lat);
6600 __tmp.put_i32_le(self.lon);
6601 __tmp.put_u16_le(self.grid_spacing);
6602 if matches!(version, MavlinkVersion::V2) {
6603 let len = __tmp.len();
6604 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6605 } else {
6606 __tmp.len()
6607 }
6608 }
6609}
6610#[doc = "id: 248"]
6611#[doc = "Message implementing parts of the V2 payload specs in V1 frames for transitional support."]
6612#[derive(Debug, Clone, PartialEq)]
6613#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6614#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6615pub struct V2_EXTENSION_DATA {
6616 #[doc = "A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to <https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml>. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase."]
6617 pub message_type: u16,
6618 #[doc = "Network ID (0 for broadcast)"]
6619 pub target_network: u8,
6620 #[doc = "System ID (0 for broadcast)"]
6621 pub target_system: u8,
6622 #[doc = "Component ID (0 for broadcast)"]
6623 pub target_component: u8,
6624 #[doc = "Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification."]
6625 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6626 pub payload: [u8; 249],
6627}
6628impl V2_EXTENSION_DATA {
6629 pub const ENCODED_LEN: usize = 254usize;
6630 pub const DEFAULT: Self = Self {
6631 message_type: 0_u16,
6632 target_network: 0_u8,
6633 target_system: 0_u8,
6634 target_component: 0_u8,
6635 payload: [0_u8; 249usize],
6636 };
6637 #[cfg(feature = "arbitrary")]
6638 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6639 use arbitrary::{Arbitrary, Unstructured};
6640 let mut buf = [0u8; 1024];
6641 rng.fill_bytes(&mut buf);
6642 let mut unstructured = Unstructured::new(&buf);
6643 Self::arbitrary(&mut unstructured).unwrap_or_default()
6644 }
6645}
6646impl Default for V2_EXTENSION_DATA {
6647 fn default() -> Self {
6648 Self::DEFAULT.clone()
6649 }
6650}
6651impl MessageData for V2_EXTENSION_DATA {
6652 type Message = MavMessage;
6653 const ID: u32 = 248u32;
6654 const NAME: &'static str = "V2_EXTENSION";
6655 const EXTRA_CRC: u8 = 8u8;
6656 const ENCODED_LEN: usize = 254usize;
6657 fn deser(
6658 _version: MavlinkVersion,
6659 __input: &[u8],
6660 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6661 let avail_len = __input.len();
6662 let mut payload_buf = [0; Self::ENCODED_LEN];
6663 let mut buf = if avail_len < Self::ENCODED_LEN {
6664 payload_buf[0..avail_len].copy_from_slice(__input);
6665 Bytes::new(&payload_buf)
6666 } else {
6667 Bytes::new(__input)
6668 };
6669 let mut __struct = Self::default();
6670 __struct.message_type = buf.get_u16_le();
6671 __struct.target_network = buf.get_u8();
6672 __struct.target_system = buf.get_u8();
6673 __struct.target_component = buf.get_u8();
6674 for v in &mut __struct.payload {
6675 let val = buf.get_u8();
6676 *v = val;
6677 }
6678 Ok(__struct)
6679 }
6680 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6681 let mut __tmp = BytesMut::new(bytes);
6682 #[allow(clippy::absurd_extreme_comparisons)]
6683 #[allow(unused_comparisons)]
6684 if __tmp.remaining() < Self::ENCODED_LEN {
6685 panic!(
6686 "buffer is too small (need {} bytes, but got {})",
6687 Self::ENCODED_LEN,
6688 __tmp.remaining(),
6689 )
6690 }
6691 __tmp.put_u16_le(self.message_type);
6692 __tmp.put_u8(self.target_network);
6693 __tmp.put_u8(self.target_system);
6694 __tmp.put_u8(self.target_component);
6695 for val in &self.payload {
6696 __tmp.put_u8(*val);
6697 }
6698 if matches!(version, MavlinkVersion::V2) {
6699 let len = __tmp.len();
6700 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6701 } else {
6702 __tmp.len()
6703 }
6704 }
6705}
6706#[doc = "id: 250"]
6707#[doc = "To debug something using a named 3D vector."]
6708#[derive(Debug, Clone, PartialEq)]
6709#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6710#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6711pub struct DEBUG_VECT_DATA {
6712 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
6713 pub time_usec: u64,
6714 #[doc = "x"]
6715 pub x: f32,
6716 #[doc = "y"]
6717 pub y: f32,
6718 #[doc = "z"]
6719 pub z: f32,
6720 #[doc = "Name"]
6721 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6722 pub name: [u8; 10],
6723}
6724impl DEBUG_VECT_DATA {
6725 pub const ENCODED_LEN: usize = 30usize;
6726 pub const DEFAULT: Self = Self {
6727 time_usec: 0_u64,
6728 x: 0.0_f32,
6729 y: 0.0_f32,
6730 z: 0.0_f32,
6731 name: [0_u8; 10usize],
6732 };
6733 #[cfg(feature = "arbitrary")]
6734 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6735 use arbitrary::{Arbitrary, Unstructured};
6736 let mut buf = [0u8; 1024];
6737 rng.fill_bytes(&mut buf);
6738 let mut unstructured = Unstructured::new(&buf);
6739 Self::arbitrary(&mut unstructured).unwrap_or_default()
6740 }
6741}
6742impl Default for DEBUG_VECT_DATA {
6743 fn default() -> Self {
6744 Self::DEFAULT.clone()
6745 }
6746}
6747impl MessageData for DEBUG_VECT_DATA {
6748 type Message = MavMessage;
6749 const ID: u32 = 250u32;
6750 const NAME: &'static str = "DEBUG_VECT";
6751 const EXTRA_CRC: u8 = 49u8;
6752 const ENCODED_LEN: usize = 30usize;
6753 fn deser(
6754 _version: MavlinkVersion,
6755 __input: &[u8],
6756 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6757 let avail_len = __input.len();
6758 let mut payload_buf = [0; Self::ENCODED_LEN];
6759 let mut buf = if avail_len < Self::ENCODED_LEN {
6760 payload_buf[0..avail_len].copy_from_slice(__input);
6761 Bytes::new(&payload_buf)
6762 } else {
6763 Bytes::new(__input)
6764 };
6765 let mut __struct = Self::default();
6766 __struct.time_usec = buf.get_u64_le();
6767 __struct.x = buf.get_f32_le();
6768 __struct.y = buf.get_f32_le();
6769 __struct.z = buf.get_f32_le();
6770 for v in &mut __struct.name {
6771 let val = buf.get_u8();
6772 *v = val;
6773 }
6774 Ok(__struct)
6775 }
6776 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6777 let mut __tmp = BytesMut::new(bytes);
6778 #[allow(clippy::absurd_extreme_comparisons)]
6779 #[allow(unused_comparisons)]
6780 if __tmp.remaining() < Self::ENCODED_LEN {
6781 panic!(
6782 "buffer is too small (need {} bytes, but got {})",
6783 Self::ENCODED_LEN,
6784 __tmp.remaining(),
6785 )
6786 }
6787 __tmp.put_u64_le(self.time_usec);
6788 __tmp.put_f32_le(self.x);
6789 __tmp.put_f32_le(self.y);
6790 __tmp.put_f32_le(self.z);
6791 for val in &self.name {
6792 __tmp.put_u8(*val);
6793 }
6794 if matches!(version, MavlinkVersion::V2) {
6795 let len = __tmp.len();
6796 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6797 } else {
6798 __tmp.len()
6799 }
6800 }
6801}
6802#[doc = "id: 69"]
6803#[doc = "This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled and buttons states are transmitted as individual on/off bits of a bitmask."]
6804#[derive(Debug, Clone, PartialEq)]
6805#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6806#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6807pub struct MANUAL_CONTROL_DATA {
6808 #[doc = "X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle."]
6809 pub x: i16,
6810 #[doc = "Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle."]
6811 pub y: i16,
6812 #[doc = "Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust."]
6813 pub z: i16,
6814 #[doc = "R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle."]
6815 pub r: i16,
6816 #[doc = "A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1."]
6817 pub buttons: u16,
6818 #[doc = "The system to be controlled."]
6819 pub target: u8,
6820 #[doc = "A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16."]
6821 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6822 pub buttons2: u16,
6823 #[doc = "Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6"]
6824 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6825 pub enabled_extensions: u8,
6826 #[doc = "Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid."]
6827 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6828 pub s: i16,
6829 #[doc = "Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid."]
6830 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6831 pub t: i16,
6832 #[doc = "Aux continuous input field 1. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 2 of enabled_extensions field is set. 0 if bit 2 is unset."]
6833 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6834 pub aux1: i16,
6835 #[doc = "Aux continuous input field 2. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 3 of enabled_extensions field is set. 0 if bit 3 is unset."]
6836 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6837 pub aux2: i16,
6838 #[doc = "Aux continuous input field 3. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 4 of enabled_extensions field is set. 0 if bit 4 is unset."]
6839 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6840 pub aux3: i16,
6841 #[doc = "Aux continuous input field 4. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 5 of enabled_extensions field is set. 0 if bit 5 is unset."]
6842 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6843 pub aux4: i16,
6844 #[doc = "Aux continuous input field 5. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 6 of enabled_extensions field is set. 0 if bit 6 is unset."]
6845 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6846 pub aux5: i16,
6847 #[doc = "Aux continuous input field 6. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 7 of enabled_extensions field is set. 0 if bit 7 is unset."]
6848 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6849 pub aux6: i16,
6850}
6851impl MANUAL_CONTROL_DATA {
6852 pub const ENCODED_LEN: usize = 30usize;
6853 pub const DEFAULT: Self = Self {
6854 x: 0_i16,
6855 y: 0_i16,
6856 z: 0_i16,
6857 r: 0_i16,
6858 buttons: 0_u16,
6859 target: 0_u8,
6860 buttons2: 0_u16,
6861 enabled_extensions: 0_u8,
6862 s: 0_i16,
6863 t: 0_i16,
6864 aux1: 0_i16,
6865 aux2: 0_i16,
6866 aux3: 0_i16,
6867 aux4: 0_i16,
6868 aux5: 0_i16,
6869 aux6: 0_i16,
6870 };
6871 #[cfg(feature = "arbitrary")]
6872 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6873 use arbitrary::{Arbitrary, Unstructured};
6874 let mut buf = [0u8; 1024];
6875 rng.fill_bytes(&mut buf);
6876 let mut unstructured = Unstructured::new(&buf);
6877 Self::arbitrary(&mut unstructured).unwrap_or_default()
6878 }
6879}
6880impl Default for MANUAL_CONTROL_DATA {
6881 fn default() -> Self {
6882 Self::DEFAULT.clone()
6883 }
6884}
6885impl MessageData for MANUAL_CONTROL_DATA {
6886 type Message = MavMessage;
6887 const ID: u32 = 69u32;
6888 const NAME: &'static str = "MANUAL_CONTROL";
6889 const EXTRA_CRC: u8 = 243u8;
6890 const ENCODED_LEN: usize = 30usize;
6891 fn deser(
6892 _version: MavlinkVersion,
6893 __input: &[u8],
6894 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6895 let avail_len = __input.len();
6896 let mut payload_buf = [0; Self::ENCODED_LEN];
6897 let mut buf = if avail_len < Self::ENCODED_LEN {
6898 payload_buf[0..avail_len].copy_from_slice(__input);
6899 Bytes::new(&payload_buf)
6900 } else {
6901 Bytes::new(__input)
6902 };
6903 let mut __struct = Self::default();
6904 __struct.x = buf.get_i16_le();
6905 __struct.y = buf.get_i16_le();
6906 __struct.z = buf.get_i16_le();
6907 __struct.r = buf.get_i16_le();
6908 __struct.buttons = buf.get_u16_le();
6909 __struct.target = buf.get_u8();
6910 __struct.buttons2 = buf.get_u16_le();
6911 __struct.enabled_extensions = buf.get_u8();
6912 __struct.s = buf.get_i16_le();
6913 __struct.t = buf.get_i16_le();
6914 __struct.aux1 = buf.get_i16_le();
6915 __struct.aux2 = buf.get_i16_le();
6916 __struct.aux3 = buf.get_i16_le();
6917 __struct.aux4 = buf.get_i16_le();
6918 __struct.aux5 = buf.get_i16_le();
6919 __struct.aux6 = buf.get_i16_le();
6920 Ok(__struct)
6921 }
6922 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6923 let mut __tmp = BytesMut::new(bytes);
6924 #[allow(clippy::absurd_extreme_comparisons)]
6925 #[allow(unused_comparisons)]
6926 if __tmp.remaining() < Self::ENCODED_LEN {
6927 panic!(
6928 "buffer is too small (need {} bytes, but got {})",
6929 Self::ENCODED_LEN,
6930 __tmp.remaining(),
6931 )
6932 }
6933 __tmp.put_i16_le(self.x);
6934 __tmp.put_i16_le(self.y);
6935 __tmp.put_i16_le(self.z);
6936 __tmp.put_i16_le(self.r);
6937 __tmp.put_u16_le(self.buttons);
6938 __tmp.put_u8(self.target);
6939 __tmp.put_u16_le(self.buttons2);
6940 __tmp.put_u8(self.enabled_extensions);
6941 __tmp.put_i16_le(self.s);
6942 __tmp.put_i16_le(self.t);
6943 __tmp.put_i16_le(self.aux1);
6944 __tmp.put_i16_le(self.aux2);
6945 __tmp.put_i16_le(self.aux3);
6946 __tmp.put_i16_le(self.aux4);
6947 __tmp.put_i16_le(self.aux5);
6948 __tmp.put_i16_le(self.aux6);
6949 if matches!(version, MavlinkVersion::V2) {
6950 let len = __tmp.len();
6951 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6952 } else {
6953 __tmp.len()
6954 }
6955 }
6956}
6957#[doc = "id: 301"]
6958#[doc = "The location and information of an AIS vessel."]
6959#[derive(Debug, Clone, PartialEq)]
6960#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6961#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6962pub struct AIS_VESSEL_DATA {
6963 #[doc = "Mobile Marine Service Identifier, 9 decimal digits"]
6964 pub MMSI: u32,
6965 #[doc = "Latitude"]
6966 pub lat: i32,
6967 #[doc = "Longitude"]
6968 pub lon: i32,
6969 #[doc = "Course over ground"]
6970 pub COG: u16,
6971 #[doc = "True heading"]
6972 pub heading: u16,
6973 #[doc = "Speed over ground"]
6974 pub velocity: u16,
6975 #[doc = "Distance from lat/lon location to bow"]
6976 pub dimension_bow: u16,
6977 #[doc = "Distance from lat/lon location to stern"]
6978 pub dimension_stern: u16,
6979 #[doc = "Time since last communication in seconds"]
6980 pub tslc: u16,
6981 #[doc = "Bitmask to indicate various statuses including valid data fields"]
6982 pub flags: AisFlags,
6983 #[doc = "Turn rate"]
6984 pub turn_rate: i8,
6985 #[doc = "Navigational status"]
6986 pub navigational_status: AisNavStatus,
6987 #[doc = "Type of vessels"]
6988 pub mavtype: AisType,
6989 #[doc = "Distance from lat/lon location to port side"]
6990 pub dimension_port: u8,
6991 #[doc = "Distance from lat/lon location to starboard side"]
6992 pub dimension_starboard: u8,
6993 #[doc = "The vessel callsign"]
6994 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6995 pub callsign: [u8; 7],
6996 #[doc = "The vessel name"]
6997 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6998 pub name: [u8; 20],
6999}
7000impl AIS_VESSEL_DATA {
7001 pub const ENCODED_LEN: usize = 58usize;
7002 pub const DEFAULT: Self = Self {
7003 MMSI: 0_u32,
7004 lat: 0_i32,
7005 lon: 0_i32,
7006 COG: 0_u16,
7007 heading: 0_u16,
7008 velocity: 0_u16,
7009 dimension_bow: 0_u16,
7010 dimension_stern: 0_u16,
7011 tslc: 0_u16,
7012 flags: AisFlags::DEFAULT,
7013 turn_rate: 0_i8,
7014 navigational_status: AisNavStatus::DEFAULT,
7015 mavtype: AisType::DEFAULT,
7016 dimension_port: 0_u8,
7017 dimension_starboard: 0_u8,
7018 callsign: [0_u8; 7usize],
7019 name: [0_u8; 20usize],
7020 };
7021 #[cfg(feature = "arbitrary")]
7022 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7023 use arbitrary::{Arbitrary, Unstructured};
7024 let mut buf = [0u8; 1024];
7025 rng.fill_bytes(&mut buf);
7026 let mut unstructured = Unstructured::new(&buf);
7027 Self::arbitrary(&mut unstructured).unwrap_or_default()
7028 }
7029}
7030impl Default for AIS_VESSEL_DATA {
7031 fn default() -> Self {
7032 Self::DEFAULT.clone()
7033 }
7034}
7035impl MessageData for AIS_VESSEL_DATA {
7036 type Message = MavMessage;
7037 const ID: u32 = 301u32;
7038 const NAME: &'static str = "AIS_VESSEL";
7039 const EXTRA_CRC: u8 = 243u8;
7040 const ENCODED_LEN: usize = 58usize;
7041 fn deser(
7042 _version: MavlinkVersion,
7043 __input: &[u8],
7044 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7045 let avail_len = __input.len();
7046 let mut payload_buf = [0; Self::ENCODED_LEN];
7047 let mut buf = if avail_len < Self::ENCODED_LEN {
7048 payload_buf[0..avail_len].copy_from_slice(__input);
7049 Bytes::new(&payload_buf)
7050 } else {
7051 Bytes::new(__input)
7052 };
7053 let mut __struct = Self::default();
7054 __struct.MMSI = buf.get_u32_le();
7055 __struct.lat = buf.get_i32_le();
7056 __struct.lon = buf.get_i32_le();
7057 __struct.COG = buf.get_u16_le();
7058 __struct.heading = buf.get_u16_le();
7059 __struct.velocity = buf.get_u16_le();
7060 __struct.dimension_bow = buf.get_u16_le();
7061 __struct.dimension_stern = buf.get_u16_le();
7062 __struct.tslc = buf.get_u16_le();
7063 let tmp = buf.get_u16_le();
7064 __struct.flags = AisFlags::from_bits(tmp & AisFlags::all().bits()).ok_or(
7065 ::mavlink_core::error::ParserError::InvalidFlag {
7066 flag_type: "AisFlags",
7067 value: tmp as u32,
7068 },
7069 )?;
7070 __struct.turn_rate = buf.get_i8();
7071 let tmp = buf.get_u8();
7072 __struct.navigational_status =
7073 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7074 enum_type: "AisNavStatus",
7075 value: tmp as u32,
7076 })?;
7077 let tmp = buf.get_u8();
7078 __struct.mavtype =
7079 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7080 enum_type: "AisType",
7081 value: tmp as u32,
7082 })?;
7083 __struct.dimension_port = buf.get_u8();
7084 __struct.dimension_starboard = buf.get_u8();
7085 for v in &mut __struct.callsign {
7086 let val = buf.get_u8();
7087 *v = val;
7088 }
7089 for v in &mut __struct.name {
7090 let val = buf.get_u8();
7091 *v = val;
7092 }
7093 Ok(__struct)
7094 }
7095 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7096 let mut __tmp = BytesMut::new(bytes);
7097 #[allow(clippy::absurd_extreme_comparisons)]
7098 #[allow(unused_comparisons)]
7099 if __tmp.remaining() < Self::ENCODED_LEN {
7100 panic!(
7101 "buffer is too small (need {} bytes, but got {})",
7102 Self::ENCODED_LEN,
7103 __tmp.remaining(),
7104 )
7105 }
7106 __tmp.put_u32_le(self.MMSI);
7107 __tmp.put_i32_le(self.lat);
7108 __tmp.put_i32_le(self.lon);
7109 __tmp.put_u16_le(self.COG);
7110 __tmp.put_u16_le(self.heading);
7111 __tmp.put_u16_le(self.velocity);
7112 __tmp.put_u16_le(self.dimension_bow);
7113 __tmp.put_u16_le(self.dimension_stern);
7114 __tmp.put_u16_le(self.tslc);
7115 __tmp.put_u16_le(self.flags.bits());
7116 __tmp.put_i8(self.turn_rate);
7117 __tmp.put_u8(self.navigational_status as u8);
7118 __tmp.put_u8(self.mavtype as u8);
7119 __tmp.put_u8(self.dimension_port);
7120 __tmp.put_u8(self.dimension_starboard);
7121 for val in &self.callsign {
7122 __tmp.put_u8(*val);
7123 }
7124 for val in &self.name {
7125 __tmp.put_u8(*val);
7126 }
7127 if matches!(version, MavlinkVersion::V2) {
7128 let len = __tmp.len();
7129 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7130 } else {
7131 __tmp.len()
7132 }
7133 }
7134}
7135#[doc = "id: 311"]
7136#[doc = "General information describing a particular UAVCAN node. Please refer to the definition of the UAVCAN service \"uavcan.protocol.GetNodeInfo\" for the background information. This message should be emitted by the system whenever a new node appears online, or an existing node reboots. Additionally, it can be emitted upon request from the other end of the MAVLink channel (see MAV_CMD_UAVCAN_GET_NODE_INFO). It is also not prohibited to emit this message unconditionally at a low frequency. The UAVCAN specification is available at <http://uavcan.org>."]
7137#[derive(Debug, Clone, PartialEq)]
7138#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7139#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7140pub struct UAVCAN_NODE_INFO_DATA {
7141 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
7142 pub time_usec: u64,
7143 #[doc = "Time since the start-up of the node."]
7144 pub uptime_sec: u32,
7145 #[doc = "Version control system (VCS) revision identifier (e.g. git short commit hash). 0 if unknown."]
7146 pub sw_vcs_commit: u32,
7147 #[doc = "Node name string. For example, \"sapog.px4.io\"."]
7148 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7149 pub name: [u8; 80],
7150 #[doc = "Hardware major version number."]
7151 pub hw_version_major: u8,
7152 #[doc = "Hardware minor version number."]
7153 pub hw_version_minor: u8,
7154 #[doc = "Hardware unique 128-bit ID."]
7155 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7156 pub hw_unique_id: [u8; 16],
7157 #[doc = "Software major version number."]
7158 pub sw_version_major: u8,
7159 #[doc = "Software minor version number."]
7160 pub sw_version_minor: u8,
7161}
7162impl UAVCAN_NODE_INFO_DATA {
7163 pub const ENCODED_LEN: usize = 116usize;
7164 pub const DEFAULT: Self = Self {
7165 time_usec: 0_u64,
7166 uptime_sec: 0_u32,
7167 sw_vcs_commit: 0_u32,
7168 name: [0_u8; 80usize],
7169 hw_version_major: 0_u8,
7170 hw_version_minor: 0_u8,
7171 hw_unique_id: [0_u8; 16usize],
7172 sw_version_major: 0_u8,
7173 sw_version_minor: 0_u8,
7174 };
7175 #[cfg(feature = "arbitrary")]
7176 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7177 use arbitrary::{Arbitrary, Unstructured};
7178 let mut buf = [0u8; 1024];
7179 rng.fill_bytes(&mut buf);
7180 let mut unstructured = Unstructured::new(&buf);
7181 Self::arbitrary(&mut unstructured).unwrap_or_default()
7182 }
7183}
7184impl Default for UAVCAN_NODE_INFO_DATA {
7185 fn default() -> Self {
7186 Self::DEFAULT.clone()
7187 }
7188}
7189impl MessageData for UAVCAN_NODE_INFO_DATA {
7190 type Message = MavMessage;
7191 const ID: u32 = 311u32;
7192 const NAME: &'static str = "UAVCAN_NODE_INFO";
7193 const EXTRA_CRC: u8 = 95u8;
7194 const ENCODED_LEN: usize = 116usize;
7195 fn deser(
7196 _version: MavlinkVersion,
7197 __input: &[u8],
7198 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7199 let avail_len = __input.len();
7200 let mut payload_buf = [0; Self::ENCODED_LEN];
7201 let mut buf = if avail_len < Self::ENCODED_LEN {
7202 payload_buf[0..avail_len].copy_from_slice(__input);
7203 Bytes::new(&payload_buf)
7204 } else {
7205 Bytes::new(__input)
7206 };
7207 let mut __struct = Self::default();
7208 __struct.time_usec = buf.get_u64_le();
7209 __struct.uptime_sec = buf.get_u32_le();
7210 __struct.sw_vcs_commit = buf.get_u32_le();
7211 for v in &mut __struct.name {
7212 let val = buf.get_u8();
7213 *v = val;
7214 }
7215 __struct.hw_version_major = buf.get_u8();
7216 __struct.hw_version_minor = buf.get_u8();
7217 for v in &mut __struct.hw_unique_id {
7218 let val = buf.get_u8();
7219 *v = val;
7220 }
7221 __struct.sw_version_major = buf.get_u8();
7222 __struct.sw_version_minor = buf.get_u8();
7223 Ok(__struct)
7224 }
7225 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7226 let mut __tmp = BytesMut::new(bytes);
7227 #[allow(clippy::absurd_extreme_comparisons)]
7228 #[allow(unused_comparisons)]
7229 if __tmp.remaining() < Self::ENCODED_LEN {
7230 panic!(
7231 "buffer is too small (need {} bytes, but got {})",
7232 Self::ENCODED_LEN,
7233 __tmp.remaining(),
7234 )
7235 }
7236 __tmp.put_u64_le(self.time_usec);
7237 __tmp.put_u32_le(self.uptime_sec);
7238 __tmp.put_u32_le(self.sw_vcs_commit);
7239 for val in &self.name {
7240 __tmp.put_u8(*val);
7241 }
7242 __tmp.put_u8(self.hw_version_major);
7243 __tmp.put_u8(self.hw_version_minor);
7244 for val in &self.hw_unique_id {
7245 __tmp.put_u8(*val);
7246 }
7247 __tmp.put_u8(self.sw_version_major);
7248 __tmp.put_u8(self.sw_version_minor);
7249 if matches!(version, MavlinkVersion::V2) {
7250 let len = __tmp.len();
7251 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7252 } else {
7253 __tmp.len()
7254 }
7255 }
7256}
7257#[doc = "id: 48"]
7258#[doc = "Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor."]
7259#[derive(Debug, Clone, PartialEq)]
7260#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7261#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7262pub struct SET_GPS_GLOBAL_ORIGIN_DATA {
7263 #[doc = "Latitude (WGS84)"]
7264 pub latitude: i32,
7265 #[doc = "Longitude (WGS84)"]
7266 pub longitude: i32,
7267 #[doc = "Altitude (MSL). Positive for up."]
7268 pub altitude: i32,
7269 #[doc = "System ID"]
7270 pub target_system: u8,
7271 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
7272 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7273 pub time_usec: u64,
7274}
7275impl SET_GPS_GLOBAL_ORIGIN_DATA {
7276 pub const ENCODED_LEN: usize = 21usize;
7277 pub const DEFAULT: Self = Self {
7278 latitude: 0_i32,
7279 longitude: 0_i32,
7280 altitude: 0_i32,
7281 target_system: 0_u8,
7282 time_usec: 0_u64,
7283 };
7284 #[cfg(feature = "arbitrary")]
7285 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7286 use arbitrary::{Arbitrary, Unstructured};
7287 let mut buf = [0u8; 1024];
7288 rng.fill_bytes(&mut buf);
7289 let mut unstructured = Unstructured::new(&buf);
7290 Self::arbitrary(&mut unstructured).unwrap_or_default()
7291 }
7292}
7293impl Default for SET_GPS_GLOBAL_ORIGIN_DATA {
7294 fn default() -> Self {
7295 Self::DEFAULT.clone()
7296 }
7297}
7298impl MessageData for SET_GPS_GLOBAL_ORIGIN_DATA {
7299 type Message = MavMessage;
7300 const ID: u32 = 48u32;
7301 const NAME: &'static str = "SET_GPS_GLOBAL_ORIGIN";
7302 const EXTRA_CRC: u8 = 41u8;
7303 const ENCODED_LEN: usize = 21usize;
7304 fn deser(
7305 _version: MavlinkVersion,
7306 __input: &[u8],
7307 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7308 let avail_len = __input.len();
7309 let mut payload_buf = [0; Self::ENCODED_LEN];
7310 let mut buf = if avail_len < Self::ENCODED_LEN {
7311 payload_buf[0..avail_len].copy_from_slice(__input);
7312 Bytes::new(&payload_buf)
7313 } else {
7314 Bytes::new(__input)
7315 };
7316 let mut __struct = Self::default();
7317 __struct.latitude = buf.get_i32_le();
7318 __struct.longitude = buf.get_i32_le();
7319 __struct.altitude = buf.get_i32_le();
7320 __struct.target_system = buf.get_u8();
7321 __struct.time_usec = buf.get_u64_le();
7322 Ok(__struct)
7323 }
7324 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7325 let mut __tmp = BytesMut::new(bytes);
7326 #[allow(clippy::absurd_extreme_comparisons)]
7327 #[allow(unused_comparisons)]
7328 if __tmp.remaining() < Self::ENCODED_LEN {
7329 panic!(
7330 "buffer is too small (need {} bytes, but got {})",
7331 Self::ENCODED_LEN,
7332 __tmp.remaining(),
7333 )
7334 }
7335 __tmp.put_i32_le(self.latitude);
7336 __tmp.put_i32_le(self.longitude);
7337 __tmp.put_i32_le(self.altitude);
7338 __tmp.put_u8(self.target_system);
7339 __tmp.put_u64_le(self.time_usec);
7340 if matches!(version, MavlinkVersion::V2) {
7341 let len = __tmp.len();
7342 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7343 } else {
7344 __tmp.len()
7345 }
7346 }
7347}
7348#[doc = "id: 137"]
7349#[doc = "Barometer readings for 2nd barometer."]
7350#[derive(Debug, Clone, PartialEq)]
7351#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7352#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7353pub struct SCALED_PRESSURE2_DATA {
7354 #[doc = "Timestamp (time since system boot)."]
7355 pub time_boot_ms: u32,
7356 #[doc = "Absolute pressure"]
7357 pub press_abs: f32,
7358 #[doc = "Differential pressure"]
7359 pub press_diff: f32,
7360 #[doc = "Absolute pressure temperature"]
7361 pub temperature: i16,
7362 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
7363 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7364 pub temperature_press_diff: i16,
7365}
7366impl SCALED_PRESSURE2_DATA {
7367 pub const ENCODED_LEN: usize = 16usize;
7368 pub const DEFAULT: Self = Self {
7369 time_boot_ms: 0_u32,
7370 press_abs: 0.0_f32,
7371 press_diff: 0.0_f32,
7372 temperature: 0_i16,
7373 temperature_press_diff: 0_i16,
7374 };
7375 #[cfg(feature = "arbitrary")]
7376 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7377 use arbitrary::{Arbitrary, Unstructured};
7378 let mut buf = [0u8; 1024];
7379 rng.fill_bytes(&mut buf);
7380 let mut unstructured = Unstructured::new(&buf);
7381 Self::arbitrary(&mut unstructured).unwrap_or_default()
7382 }
7383}
7384impl Default for SCALED_PRESSURE2_DATA {
7385 fn default() -> Self {
7386 Self::DEFAULT.clone()
7387 }
7388}
7389impl MessageData for SCALED_PRESSURE2_DATA {
7390 type Message = MavMessage;
7391 const ID: u32 = 137u32;
7392 const NAME: &'static str = "SCALED_PRESSURE2";
7393 const EXTRA_CRC: u8 = 195u8;
7394 const ENCODED_LEN: usize = 16usize;
7395 fn deser(
7396 _version: MavlinkVersion,
7397 __input: &[u8],
7398 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7399 let avail_len = __input.len();
7400 let mut payload_buf = [0; Self::ENCODED_LEN];
7401 let mut buf = if avail_len < Self::ENCODED_LEN {
7402 payload_buf[0..avail_len].copy_from_slice(__input);
7403 Bytes::new(&payload_buf)
7404 } else {
7405 Bytes::new(__input)
7406 };
7407 let mut __struct = Self::default();
7408 __struct.time_boot_ms = buf.get_u32_le();
7409 __struct.press_abs = buf.get_f32_le();
7410 __struct.press_diff = buf.get_f32_le();
7411 __struct.temperature = buf.get_i16_le();
7412 __struct.temperature_press_diff = buf.get_i16_le();
7413 Ok(__struct)
7414 }
7415 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7416 let mut __tmp = BytesMut::new(bytes);
7417 #[allow(clippy::absurd_extreme_comparisons)]
7418 #[allow(unused_comparisons)]
7419 if __tmp.remaining() < Self::ENCODED_LEN {
7420 panic!(
7421 "buffer is too small (need {} bytes, but got {})",
7422 Self::ENCODED_LEN,
7423 __tmp.remaining(),
7424 )
7425 }
7426 __tmp.put_u32_le(self.time_boot_ms);
7427 __tmp.put_f32_le(self.press_abs);
7428 __tmp.put_f32_le(self.press_diff);
7429 __tmp.put_i16_le(self.temperature);
7430 __tmp.put_i16_le(self.temperature_press_diff);
7431 if matches!(version, MavlinkVersion::V2) {
7432 let len = __tmp.len();
7433 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7434 } else {
7435 __tmp.len()
7436 }
7437 }
7438}
7439#[doc = "id: 262"]
7440#[doc = "Information about the status of a capture. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
7441#[derive(Debug, Clone, PartialEq)]
7442#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7443#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7444pub struct CAMERA_CAPTURE_STATUS_DATA {
7445 #[doc = "Timestamp (time since system boot)."]
7446 pub time_boot_ms: u32,
7447 #[doc = "Image capture interval"]
7448 pub image_interval: f32,
7449 #[doc = "Elapsed time since recording started (0: Not supported/available). A GCS should compute recording time and use non-zero values of this field to correct any discrepancy."]
7450 pub recording_time_ms: u32,
7451 #[doc = "Available storage capacity."]
7452 pub available_capacity: f32,
7453 #[doc = "Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)"]
7454 pub image_status: u8,
7455 #[doc = "Current status of video capturing (0: idle, 1: capture in progress)"]
7456 pub video_status: u8,
7457 #[doc = "Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT)."]
7458 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7459 pub image_count: i32,
7460 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
7461 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7462 pub camera_device_id: u8,
7463}
7464impl CAMERA_CAPTURE_STATUS_DATA {
7465 pub const ENCODED_LEN: usize = 23usize;
7466 pub const DEFAULT: Self = Self {
7467 time_boot_ms: 0_u32,
7468 image_interval: 0.0_f32,
7469 recording_time_ms: 0_u32,
7470 available_capacity: 0.0_f32,
7471 image_status: 0_u8,
7472 video_status: 0_u8,
7473 image_count: 0_i32,
7474 camera_device_id: 0_u8,
7475 };
7476 #[cfg(feature = "arbitrary")]
7477 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7478 use arbitrary::{Arbitrary, Unstructured};
7479 let mut buf = [0u8; 1024];
7480 rng.fill_bytes(&mut buf);
7481 let mut unstructured = Unstructured::new(&buf);
7482 Self::arbitrary(&mut unstructured).unwrap_or_default()
7483 }
7484}
7485impl Default for CAMERA_CAPTURE_STATUS_DATA {
7486 fn default() -> Self {
7487 Self::DEFAULT.clone()
7488 }
7489}
7490impl MessageData for CAMERA_CAPTURE_STATUS_DATA {
7491 type Message = MavMessage;
7492 const ID: u32 = 262u32;
7493 const NAME: &'static str = "CAMERA_CAPTURE_STATUS";
7494 const EXTRA_CRC: u8 = 12u8;
7495 const ENCODED_LEN: usize = 23usize;
7496 fn deser(
7497 _version: MavlinkVersion,
7498 __input: &[u8],
7499 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7500 let avail_len = __input.len();
7501 let mut payload_buf = [0; Self::ENCODED_LEN];
7502 let mut buf = if avail_len < Self::ENCODED_LEN {
7503 payload_buf[0..avail_len].copy_from_slice(__input);
7504 Bytes::new(&payload_buf)
7505 } else {
7506 Bytes::new(__input)
7507 };
7508 let mut __struct = Self::default();
7509 __struct.time_boot_ms = buf.get_u32_le();
7510 __struct.image_interval = buf.get_f32_le();
7511 __struct.recording_time_ms = buf.get_u32_le();
7512 __struct.available_capacity = buf.get_f32_le();
7513 __struct.image_status = buf.get_u8();
7514 __struct.video_status = buf.get_u8();
7515 __struct.image_count = buf.get_i32_le();
7516 __struct.camera_device_id = buf.get_u8();
7517 Ok(__struct)
7518 }
7519 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7520 let mut __tmp = BytesMut::new(bytes);
7521 #[allow(clippy::absurd_extreme_comparisons)]
7522 #[allow(unused_comparisons)]
7523 if __tmp.remaining() < Self::ENCODED_LEN {
7524 panic!(
7525 "buffer is too small (need {} bytes, but got {})",
7526 Self::ENCODED_LEN,
7527 __tmp.remaining(),
7528 )
7529 }
7530 __tmp.put_u32_le(self.time_boot_ms);
7531 __tmp.put_f32_le(self.image_interval);
7532 __tmp.put_u32_le(self.recording_time_ms);
7533 __tmp.put_f32_le(self.available_capacity);
7534 __tmp.put_u8(self.image_status);
7535 __tmp.put_u8(self.video_status);
7536 __tmp.put_i32_le(self.image_count);
7537 __tmp.put_u8(self.camera_device_id);
7538 if matches!(version, MavlinkVersion::V2) {
7539 let len = __tmp.len();
7540 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7541 } else {
7542 __tmp.len()
7543 }
7544 }
7545}
7546#[doc = "id: 299"]
7547#[doc = "Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
7548#[derive(Debug, Clone, PartialEq)]
7549#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7550#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7551pub struct WIFI_CONFIG_AP_DATA {
7552 #[doc = "Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response."]
7553 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7554 pub ssid: [u8; 32],
7555 #[doc = "Password. Blank for an open AP. MD5 hash when message is sent back as a response."]
7556 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7557 pub password: [u8; 64],
7558 #[doc = "WiFi Mode."]
7559 #[cfg_attr(feature = "serde", serde(default))]
7560 pub mode: WifiConfigApMode,
7561 #[doc = "Message acceptance response (sent back to GS)."]
7562 #[cfg_attr(feature = "serde", serde(default))]
7563 pub response: WifiConfigApResponse,
7564}
7565impl WIFI_CONFIG_AP_DATA {
7566 pub const ENCODED_LEN: usize = 98usize;
7567 pub const DEFAULT: Self = Self {
7568 ssid: [0_u8; 32usize],
7569 password: [0_u8; 64usize],
7570 mode: WifiConfigApMode::DEFAULT,
7571 response: WifiConfigApResponse::DEFAULT,
7572 };
7573 #[cfg(feature = "arbitrary")]
7574 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7575 use arbitrary::{Arbitrary, Unstructured};
7576 let mut buf = [0u8; 1024];
7577 rng.fill_bytes(&mut buf);
7578 let mut unstructured = Unstructured::new(&buf);
7579 Self::arbitrary(&mut unstructured).unwrap_or_default()
7580 }
7581}
7582impl Default for WIFI_CONFIG_AP_DATA {
7583 fn default() -> Self {
7584 Self::DEFAULT.clone()
7585 }
7586}
7587impl MessageData for WIFI_CONFIG_AP_DATA {
7588 type Message = MavMessage;
7589 const ID: u32 = 299u32;
7590 const NAME: &'static str = "WIFI_CONFIG_AP";
7591 const EXTRA_CRC: u8 = 19u8;
7592 const ENCODED_LEN: usize = 98usize;
7593 fn deser(
7594 _version: MavlinkVersion,
7595 __input: &[u8],
7596 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7597 let avail_len = __input.len();
7598 let mut payload_buf = [0; Self::ENCODED_LEN];
7599 let mut buf = if avail_len < Self::ENCODED_LEN {
7600 payload_buf[0..avail_len].copy_from_slice(__input);
7601 Bytes::new(&payload_buf)
7602 } else {
7603 Bytes::new(__input)
7604 };
7605 let mut __struct = Self::default();
7606 for v in &mut __struct.ssid {
7607 let val = buf.get_u8();
7608 *v = val;
7609 }
7610 for v in &mut __struct.password {
7611 let val = buf.get_u8();
7612 *v = val;
7613 }
7614 let tmp = buf.get_i8();
7615 __struct.mode =
7616 FromPrimitive::from_i8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7617 enum_type: "WifiConfigApMode",
7618 value: tmp as u32,
7619 })?;
7620 let tmp = buf.get_i8();
7621 __struct.response =
7622 FromPrimitive::from_i8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7623 enum_type: "WifiConfigApResponse",
7624 value: tmp as u32,
7625 })?;
7626 Ok(__struct)
7627 }
7628 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7629 let mut __tmp = BytesMut::new(bytes);
7630 #[allow(clippy::absurd_extreme_comparisons)]
7631 #[allow(unused_comparisons)]
7632 if __tmp.remaining() < Self::ENCODED_LEN {
7633 panic!(
7634 "buffer is too small (need {} bytes, but got {})",
7635 Self::ENCODED_LEN,
7636 __tmp.remaining(),
7637 )
7638 }
7639 for val in &self.ssid {
7640 __tmp.put_u8(*val);
7641 }
7642 for val in &self.password {
7643 __tmp.put_u8(*val);
7644 }
7645 __tmp.put_i8(self.mode as i8);
7646 __tmp.put_i8(self.response as i8);
7647 if matches!(version, MavlinkVersion::V2) {
7648 let len = __tmp.len();
7649 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7650 } else {
7651 __tmp.len()
7652 }
7653 }
7654}
7655#[doc = "id: 43"]
7656#[doc = "Request the overall list of mission items from the system/component."]
7657#[derive(Debug, Clone, PartialEq)]
7658#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7659#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7660pub struct MISSION_REQUEST_LIST_DATA {
7661 #[doc = "System ID"]
7662 pub target_system: u8,
7663 #[doc = "Component ID"]
7664 pub target_component: u8,
7665 #[doc = "Mission type."]
7666 #[cfg_attr(feature = "serde", serde(default))]
7667 pub mission_type: MavMissionType,
7668}
7669impl MISSION_REQUEST_LIST_DATA {
7670 pub const ENCODED_LEN: usize = 3usize;
7671 pub const DEFAULT: Self = Self {
7672 target_system: 0_u8,
7673 target_component: 0_u8,
7674 mission_type: MavMissionType::DEFAULT,
7675 };
7676 #[cfg(feature = "arbitrary")]
7677 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7678 use arbitrary::{Arbitrary, Unstructured};
7679 let mut buf = [0u8; 1024];
7680 rng.fill_bytes(&mut buf);
7681 let mut unstructured = Unstructured::new(&buf);
7682 Self::arbitrary(&mut unstructured).unwrap_or_default()
7683 }
7684}
7685impl Default for MISSION_REQUEST_LIST_DATA {
7686 fn default() -> Self {
7687 Self::DEFAULT.clone()
7688 }
7689}
7690impl MessageData for MISSION_REQUEST_LIST_DATA {
7691 type Message = MavMessage;
7692 const ID: u32 = 43u32;
7693 const NAME: &'static str = "MISSION_REQUEST_LIST";
7694 const EXTRA_CRC: u8 = 132u8;
7695 const ENCODED_LEN: usize = 3usize;
7696 fn deser(
7697 _version: MavlinkVersion,
7698 __input: &[u8],
7699 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7700 let avail_len = __input.len();
7701 let mut payload_buf = [0; Self::ENCODED_LEN];
7702 let mut buf = if avail_len < Self::ENCODED_LEN {
7703 payload_buf[0..avail_len].copy_from_slice(__input);
7704 Bytes::new(&payload_buf)
7705 } else {
7706 Bytes::new(__input)
7707 };
7708 let mut __struct = Self::default();
7709 __struct.target_system = buf.get_u8();
7710 __struct.target_component = buf.get_u8();
7711 let tmp = buf.get_u8();
7712 __struct.mission_type =
7713 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7714 enum_type: "MavMissionType",
7715 value: tmp as u32,
7716 })?;
7717 Ok(__struct)
7718 }
7719 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7720 let mut __tmp = BytesMut::new(bytes);
7721 #[allow(clippy::absurd_extreme_comparisons)]
7722 #[allow(unused_comparisons)]
7723 if __tmp.remaining() < Self::ENCODED_LEN {
7724 panic!(
7725 "buffer is too small (need {} bytes, but got {})",
7726 Self::ENCODED_LEN,
7727 __tmp.remaining(),
7728 )
7729 }
7730 __tmp.put_u8(self.target_system);
7731 __tmp.put_u8(self.target_component);
7732 __tmp.put_u8(self.mission_type as u8);
7733 if matches!(version, MavlinkVersion::V2) {
7734 let len = __tmp.len();
7735 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7736 } else {
7737 __tmp.len()
7738 }
7739 }
7740}
7741#[doc = "id: 47"]
7742#[doc = "Acknowledgment message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero)."]
7743#[derive(Debug, Clone, PartialEq)]
7744#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7745#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7746pub struct MISSION_ACK_DATA {
7747 #[doc = "System ID"]
7748 pub target_system: u8,
7749 #[doc = "Component ID"]
7750 pub target_component: u8,
7751 #[doc = "Mission result."]
7752 pub mavtype: MavMissionResult,
7753 #[doc = "Mission type."]
7754 #[cfg_attr(feature = "serde", serde(default))]
7755 pub mission_type: MavMissionType,
7756 #[doc = "Id of new on-vehicle mission, fence, or rally point plan (on upload to vehicle). The id is calculated and returned by a vehicle when a new plan is uploaded by a GCS. The only requirement on the id is that it must change when there is any change to the on-vehicle plan type (there is no requirement that the id be globally unique). 0 on download from the vehicle to the GCS (on download the ID is set in MISSION_COUNT). 0 if plan ids are not supported. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded."]
7757 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7758 pub opaque_id: u32,
7759}
7760impl MISSION_ACK_DATA {
7761 pub const ENCODED_LEN: usize = 8usize;
7762 pub const DEFAULT: Self = Self {
7763 target_system: 0_u8,
7764 target_component: 0_u8,
7765 mavtype: MavMissionResult::DEFAULT,
7766 mission_type: MavMissionType::DEFAULT,
7767 opaque_id: 0_u32,
7768 };
7769 #[cfg(feature = "arbitrary")]
7770 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7771 use arbitrary::{Arbitrary, Unstructured};
7772 let mut buf = [0u8; 1024];
7773 rng.fill_bytes(&mut buf);
7774 let mut unstructured = Unstructured::new(&buf);
7775 Self::arbitrary(&mut unstructured).unwrap_or_default()
7776 }
7777}
7778impl Default for MISSION_ACK_DATA {
7779 fn default() -> Self {
7780 Self::DEFAULT.clone()
7781 }
7782}
7783impl MessageData for MISSION_ACK_DATA {
7784 type Message = MavMessage;
7785 const ID: u32 = 47u32;
7786 const NAME: &'static str = "MISSION_ACK";
7787 const EXTRA_CRC: u8 = 153u8;
7788 const ENCODED_LEN: usize = 8usize;
7789 fn deser(
7790 _version: MavlinkVersion,
7791 __input: &[u8],
7792 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7793 let avail_len = __input.len();
7794 let mut payload_buf = [0; Self::ENCODED_LEN];
7795 let mut buf = if avail_len < Self::ENCODED_LEN {
7796 payload_buf[0..avail_len].copy_from_slice(__input);
7797 Bytes::new(&payload_buf)
7798 } else {
7799 Bytes::new(__input)
7800 };
7801 let mut __struct = Self::default();
7802 __struct.target_system = buf.get_u8();
7803 __struct.target_component = buf.get_u8();
7804 let tmp = buf.get_u8();
7805 __struct.mavtype =
7806 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7807 enum_type: "MavMissionResult",
7808 value: tmp as u32,
7809 })?;
7810 let tmp = buf.get_u8();
7811 __struct.mission_type =
7812 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7813 enum_type: "MavMissionType",
7814 value: tmp as u32,
7815 })?;
7816 __struct.opaque_id = buf.get_u32_le();
7817 Ok(__struct)
7818 }
7819 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7820 let mut __tmp = BytesMut::new(bytes);
7821 #[allow(clippy::absurd_extreme_comparisons)]
7822 #[allow(unused_comparisons)]
7823 if __tmp.remaining() < Self::ENCODED_LEN {
7824 panic!(
7825 "buffer is too small (need {} bytes, but got {})",
7826 Self::ENCODED_LEN,
7827 __tmp.remaining(),
7828 )
7829 }
7830 __tmp.put_u8(self.target_system);
7831 __tmp.put_u8(self.target_component);
7832 __tmp.put_u8(self.mavtype as u8);
7833 __tmp.put_u8(self.mission_type as u8);
7834 __tmp.put_u32_le(self.opaque_id);
7835 if matches!(version, MavlinkVersion::V2) {
7836 let len = __tmp.len();
7837 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7838 } else {
7839 __tmp.len()
7840 }
7841 }
7842}
7843#[doc = "id: 131"]
7844#[doc = "Data packet for images sent using the Image Transmission Protocol: <https://mavlink.io/en/services/image_transmission.html>."]
7845#[derive(Debug, Clone, PartialEq)]
7846#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7847#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7848pub struct ENCAPSULATED_DATA_DATA {
7849 #[doc = "sequence number (starting with 0 on every transmission)"]
7850 pub seqnr: u16,
7851 #[doc = "image data bytes"]
7852 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7853 pub data: [u8; 253],
7854}
7855impl ENCAPSULATED_DATA_DATA {
7856 pub const ENCODED_LEN: usize = 255usize;
7857 pub const DEFAULT: Self = Self {
7858 seqnr: 0_u16,
7859 data: [0_u8; 253usize],
7860 };
7861 #[cfg(feature = "arbitrary")]
7862 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7863 use arbitrary::{Arbitrary, Unstructured};
7864 let mut buf = [0u8; 1024];
7865 rng.fill_bytes(&mut buf);
7866 let mut unstructured = Unstructured::new(&buf);
7867 Self::arbitrary(&mut unstructured).unwrap_or_default()
7868 }
7869}
7870impl Default for ENCAPSULATED_DATA_DATA {
7871 fn default() -> Self {
7872 Self::DEFAULT.clone()
7873 }
7874}
7875impl MessageData for ENCAPSULATED_DATA_DATA {
7876 type Message = MavMessage;
7877 const ID: u32 = 131u32;
7878 const NAME: &'static str = "ENCAPSULATED_DATA";
7879 const EXTRA_CRC: u8 = 223u8;
7880 const ENCODED_LEN: usize = 255usize;
7881 fn deser(
7882 _version: MavlinkVersion,
7883 __input: &[u8],
7884 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7885 let avail_len = __input.len();
7886 let mut payload_buf = [0; Self::ENCODED_LEN];
7887 let mut buf = if avail_len < Self::ENCODED_LEN {
7888 payload_buf[0..avail_len].copy_from_slice(__input);
7889 Bytes::new(&payload_buf)
7890 } else {
7891 Bytes::new(__input)
7892 };
7893 let mut __struct = Self::default();
7894 __struct.seqnr = buf.get_u16_le();
7895 for v in &mut __struct.data {
7896 let val = buf.get_u8();
7897 *v = val;
7898 }
7899 Ok(__struct)
7900 }
7901 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7902 let mut __tmp = BytesMut::new(bytes);
7903 #[allow(clippy::absurd_extreme_comparisons)]
7904 #[allow(unused_comparisons)]
7905 if __tmp.remaining() < Self::ENCODED_LEN {
7906 panic!(
7907 "buffer is too small (need {} bytes, but got {})",
7908 Self::ENCODED_LEN,
7909 __tmp.remaining(),
7910 )
7911 }
7912 __tmp.put_u16_le(self.seqnr);
7913 for val in &self.data {
7914 __tmp.put_u8(*val);
7915 }
7916 if matches!(version, MavlinkVersion::V2) {
7917 let len = __tmp.len();
7918 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7919 } else {
7920 __tmp.len()
7921 }
7922 }
7923}
7924#[doc = "id: 10001"]
7925#[doc = "Static data to configure the ADS-B transponder (send within 10 sec of a POR and every 10 sec thereafter)."]
7926#[derive(Debug, Clone, PartialEq)]
7927#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7928#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7929pub struct UAVIONIX_ADSB_OUT_CFG_DATA {
7930 #[doc = "Vehicle address (24 bit)"]
7931 pub ICAO: u32,
7932 #[doc = "Aircraft stall speed in cm/s"]
7933 pub stallSpeed: u16,
7934 #[doc = "Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, \" \" only)"]
7935 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7936 pub callsign: [u8; 9],
7937 #[doc = "Transmitting vehicle type. See ADSB_EMITTER_TYPE enum"]
7938 pub emitterType: AdsbEmitterType,
7939 #[doc = "Aircraft length and width encoding (table 2-35 of DO-282B)"]
7940 pub aircraftSize: UavionixAdsbOutCfgAircraftSize,
7941 #[doc = "GPS antenna lateral offset (table 2-36 of DO-282B)"]
7942 pub gpsOffsetLat: UavionixAdsbOutCfgGpsOffsetLat,
7943 #[doc = "GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B)"]
7944 pub gpsOffsetLon: UavionixAdsbOutCfgGpsOffsetLon,
7945 #[doc = "ADS-B transponder reciever and transmit enable flags"]
7946 pub rfSelect: UavionixAdsbOutRfSelect,
7947}
7948impl UAVIONIX_ADSB_OUT_CFG_DATA {
7949 pub const ENCODED_LEN: usize = 20usize;
7950 pub const DEFAULT: Self = Self {
7951 ICAO: 0_u32,
7952 stallSpeed: 0_u16,
7953 callsign: [0_u8; 9usize],
7954 emitterType: AdsbEmitterType::DEFAULT,
7955 aircraftSize: UavionixAdsbOutCfgAircraftSize::DEFAULT,
7956 gpsOffsetLat: UavionixAdsbOutCfgGpsOffsetLat::DEFAULT,
7957 gpsOffsetLon: UavionixAdsbOutCfgGpsOffsetLon::DEFAULT,
7958 rfSelect: UavionixAdsbOutRfSelect::DEFAULT,
7959 };
7960 #[cfg(feature = "arbitrary")]
7961 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7962 use arbitrary::{Arbitrary, Unstructured};
7963 let mut buf = [0u8; 1024];
7964 rng.fill_bytes(&mut buf);
7965 let mut unstructured = Unstructured::new(&buf);
7966 Self::arbitrary(&mut unstructured).unwrap_or_default()
7967 }
7968}
7969impl Default for UAVIONIX_ADSB_OUT_CFG_DATA {
7970 fn default() -> Self {
7971 Self::DEFAULT.clone()
7972 }
7973}
7974impl MessageData for UAVIONIX_ADSB_OUT_CFG_DATA {
7975 type Message = MavMessage;
7976 const ID: u32 = 10001u32;
7977 const NAME: &'static str = "UAVIONIX_ADSB_OUT_CFG";
7978 const EXTRA_CRC: u8 = 209u8;
7979 const ENCODED_LEN: usize = 20usize;
7980 fn deser(
7981 _version: MavlinkVersion,
7982 __input: &[u8],
7983 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7984 let avail_len = __input.len();
7985 let mut payload_buf = [0; Self::ENCODED_LEN];
7986 let mut buf = if avail_len < Self::ENCODED_LEN {
7987 payload_buf[0..avail_len].copy_from_slice(__input);
7988 Bytes::new(&payload_buf)
7989 } else {
7990 Bytes::new(__input)
7991 };
7992 let mut __struct = Self::default();
7993 __struct.ICAO = buf.get_u32_le();
7994 __struct.stallSpeed = buf.get_u16_le();
7995 for v in &mut __struct.callsign {
7996 let val = buf.get_u8();
7997 *v = val;
7998 }
7999 let tmp = buf.get_u8();
8000 __struct.emitterType =
8001 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8002 enum_type: "AdsbEmitterType",
8003 value: tmp as u32,
8004 })?;
8005 let tmp = buf.get_u8();
8006 __struct.aircraftSize =
8007 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8008 enum_type: "UavionixAdsbOutCfgAircraftSize",
8009 value: tmp as u32,
8010 })?;
8011 let tmp = buf.get_u8();
8012 __struct.gpsOffsetLat =
8013 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8014 enum_type: "UavionixAdsbOutCfgGpsOffsetLat",
8015 value: tmp as u32,
8016 })?;
8017 let tmp = buf.get_u8();
8018 __struct.gpsOffsetLon =
8019 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8020 enum_type: "UavionixAdsbOutCfgGpsOffsetLon",
8021 value: tmp as u32,
8022 })?;
8023 let tmp = buf.get_u8();
8024 __struct.rfSelect = UavionixAdsbOutRfSelect::from_bits(
8025 tmp & UavionixAdsbOutRfSelect::all().bits(),
8026 )
8027 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
8028 flag_type: "UavionixAdsbOutRfSelect",
8029 value: tmp as u32,
8030 })?;
8031 Ok(__struct)
8032 }
8033 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8034 let mut __tmp = BytesMut::new(bytes);
8035 #[allow(clippy::absurd_extreme_comparisons)]
8036 #[allow(unused_comparisons)]
8037 if __tmp.remaining() < Self::ENCODED_LEN {
8038 panic!(
8039 "buffer is too small (need {} bytes, but got {})",
8040 Self::ENCODED_LEN,
8041 __tmp.remaining(),
8042 )
8043 }
8044 __tmp.put_u32_le(self.ICAO);
8045 __tmp.put_u16_le(self.stallSpeed);
8046 for val in &self.callsign {
8047 __tmp.put_u8(*val);
8048 }
8049 __tmp.put_u8(self.emitterType as u8);
8050 __tmp.put_u8(self.aircraftSize as u8);
8051 __tmp.put_u8(self.gpsOffsetLat as u8);
8052 __tmp.put_u8(self.gpsOffsetLon as u8);
8053 __tmp.put_u8(self.rfSelect.bits());
8054 if matches!(version, MavlinkVersion::V2) {
8055 let len = __tmp.len();
8056 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8057 } else {
8058 __tmp.len()
8059 }
8060 }
8061}
8062#[doc = "id: 225"]
8063#[doc = "EFI status output."]
8064#[derive(Debug, Clone, PartialEq)]
8065#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8066#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8067pub struct EFI_STATUS_DATA {
8068 #[doc = "ECU index"]
8069 pub ecu_index: f32,
8070 #[doc = "RPM"]
8071 pub rpm: f32,
8072 #[doc = "Fuel consumed"]
8073 pub fuel_consumed: f32,
8074 #[doc = "Fuel flow rate"]
8075 pub fuel_flow: f32,
8076 #[doc = "Engine load"]
8077 pub engine_load: f32,
8078 #[doc = "Throttle position"]
8079 pub throttle_position: f32,
8080 #[doc = "Spark dwell time"]
8081 pub spark_dwell_time: f32,
8082 #[doc = "Barometric pressure"]
8083 pub barometric_pressure: f32,
8084 #[doc = "Intake manifold pressure("]
8085 pub intake_manifold_pressure: f32,
8086 #[doc = "Intake manifold temperature"]
8087 pub intake_manifold_temperature: f32,
8088 #[doc = "Cylinder head temperature"]
8089 pub cylinder_head_temperature: f32,
8090 #[doc = "Ignition timing (Crank angle degrees)"]
8091 pub ignition_timing: f32,
8092 #[doc = "Injection time"]
8093 pub injection_time: f32,
8094 #[doc = "Exhaust gas temperature"]
8095 pub exhaust_gas_temperature: f32,
8096 #[doc = "Output throttle"]
8097 pub throttle_out: f32,
8098 #[doc = "Pressure/temperature compensation"]
8099 pub pt_compensation: f32,
8100 #[doc = "EFI health status"]
8101 pub health: u8,
8102 #[doc = "Supply voltage to EFI sparking system. Zero in this value means \"unknown\", so if the supply voltage really is zero volts use 0.0001 instead."]
8103 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8104 pub ignition_voltage: f32,
8105 #[doc = "Fuel pressure. Zero in this value means \"unknown\", so if the fuel pressure really is zero kPa use 0.0001 instead."]
8106 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8107 pub fuel_pressure: f32,
8108}
8109impl EFI_STATUS_DATA {
8110 pub const ENCODED_LEN: usize = 73usize;
8111 pub const DEFAULT: Self = Self {
8112 ecu_index: 0.0_f32,
8113 rpm: 0.0_f32,
8114 fuel_consumed: 0.0_f32,
8115 fuel_flow: 0.0_f32,
8116 engine_load: 0.0_f32,
8117 throttle_position: 0.0_f32,
8118 spark_dwell_time: 0.0_f32,
8119 barometric_pressure: 0.0_f32,
8120 intake_manifold_pressure: 0.0_f32,
8121 intake_manifold_temperature: 0.0_f32,
8122 cylinder_head_temperature: 0.0_f32,
8123 ignition_timing: 0.0_f32,
8124 injection_time: 0.0_f32,
8125 exhaust_gas_temperature: 0.0_f32,
8126 throttle_out: 0.0_f32,
8127 pt_compensation: 0.0_f32,
8128 health: 0_u8,
8129 ignition_voltage: 0.0_f32,
8130 fuel_pressure: 0.0_f32,
8131 };
8132 #[cfg(feature = "arbitrary")]
8133 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8134 use arbitrary::{Arbitrary, Unstructured};
8135 let mut buf = [0u8; 1024];
8136 rng.fill_bytes(&mut buf);
8137 let mut unstructured = Unstructured::new(&buf);
8138 Self::arbitrary(&mut unstructured).unwrap_or_default()
8139 }
8140}
8141impl Default for EFI_STATUS_DATA {
8142 fn default() -> Self {
8143 Self::DEFAULT.clone()
8144 }
8145}
8146impl MessageData for EFI_STATUS_DATA {
8147 type Message = MavMessage;
8148 const ID: u32 = 225u32;
8149 const NAME: &'static str = "EFI_STATUS";
8150 const EXTRA_CRC: u8 = 208u8;
8151 const ENCODED_LEN: usize = 73usize;
8152 fn deser(
8153 _version: MavlinkVersion,
8154 __input: &[u8],
8155 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8156 let avail_len = __input.len();
8157 let mut payload_buf = [0; Self::ENCODED_LEN];
8158 let mut buf = if avail_len < Self::ENCODED_LEN {
8159 payload_buf[0..avail_len].copy_from_slice(__input);
8160 Bytes::new(&payload_buf)
8161 } else {
8162 Bytes::new(__input)
8163 };
8164 let mut __struct = Self::default();
8165 __struct.ecu_index = buf.get_f32_le();
8166 __struct.rpm = buf.get_f32_le();
8167 __struct.fuel_consumed = buf.get_f32_le();
8168 __struct.fuel_flow = buf.get_f32_le();
8169 __struct.engine_load = buf.get_f32_le();
8170 __struct.throttle_position = buf.get_f32_le();
8171 __struct.spark_dwell_time = buf.get_f32_le();
8172 __struct.barometric_pressure = buf.get_f32_le();
8173 __struct.intake_manifold_pressure = buf.get_f32_le();
8174 __struct.intake_manifold_temperature = buf.get_f32_le();
8175 __struct.cylinder_head_temperature = buf.get_f32_le();
8176 __struct.ignition_timing = buf.get_f32_le();
8177 __struct.injection_time = buf.get_f32_le();
8178 __struct.exhaust_gas_temperature = buf.get_f32_le();
8179 __struct.throttle_out = buf.get_f32_le();
8180 __struct.pt_compensation = buf.get_f32_le();
8181 __struct.health = buf.get_u8();
8182 __struct.ignition_voltage = buf.get_f32_le();
8183 __struct.fuel_pressure = buf.get_f32_le();
8184 Ok(__struct)
8185 }
8186 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8187 let mut __tmp = BytesMut::new(bytes);
8188 #[allow(clippy::absurd_extreme_comparisons)]
8189 #[allow(unused_comparisons)]
8190 if __tmp.remaining() < Self::ENCODED_LEN {
8191 panic!(
8192 "buffer is too small (need {} bytes, but got {})",
8193 Self::ENCODED_LEN,
8194 __tmp.remaining(),
8195 )
8196 }
8197 __tmp.put_f32_le(self.ecu_index);
8198 __tmp.put_f32_le(self.rpm);
8199 __tmp.put_f32_le(self.fuel_consumed);
8200 __tmp.put_f32_le(self.fuel_flow);
8201 __tmp.put_f32_le(self.engine_load);
8202 __tmp.put_f32_le(self.throttle_position);
8203 __tmp.put_f32_le(self.spark_dwell_time);
8204 __tmp.put_f32_le(self.barometric_pressure);
8205 __tmp.put_f32_le(self.intake_manifold_pressure);
8206 __tmp.put_f32_le(self.intake_manifold_temperature);
8207 __tmp.put_f32_le(self.cylinder_head_temperature);
8208 __tmp.put_f32_le(self.ignition_timing);
8209 __tmp.put_f32_le(self.injection_time);
8210 __tmp.put_f32_le(self.exhaust_gas_temperature);
8211 __tmp.put_f32_le(self.throttle_out);
8212 __tmp.put_f32_le(self.pt_compensation);
8213 __tmp.put_u8(self.health);
8214 __tmp.put_f32_le(self.ignition_voltage);
8215 __tmp.put_f32_le(self.fuel_pressure);
8216 if matches!(version, MavlinkVersion::V2) {
8217 let len = __tmp.len();
8218 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8219 } else {
8220 __tmp.len()
8221 }
8222 }
8223}
8224#[doc = "id: 12901"]
8225#[doc = "Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft."]
8226#[derive(Debug, Clone, PartialEq)]
8227#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8228#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8229pub struct OPEN_DRONE_ID_LOCATION_DATA {
8230 #[doc = "Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon)."]
8231 pub latitude: i32,
8232 #[doc = "Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon)."]
8233 pub longitude: i32,
8234 #[doc = "The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m."]
8235 pub altitude_barometric: f32,
8236 #[doc = "The geodetic altitude as defined by WGS84. If unknown: -1000 m."]
8237 pub altitude_geodetic: f32,
8238 #[doc = "The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m."]
8239 pub height: f32,
8240 #[doc = "Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF."]
8241 pub timestamp: f32,
8242 #[doc = "Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees."]
8243 pub direction: u16,
8244 #[doc = "Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s."]
8245 pub speed_horizontal: u16,
8246 #[doc = "The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s."]
8247 pub speed_vertical: i16,
8248 #[doc = "System ID (0 for broadcast)."]
8249 pub target_system: u8,
8250 #[doc = "Component ID (0 for broadcast)."]
8251 pub target_component: u8,
8252 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
8253 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8254 pub id_or_mac: [u8; 20],
8255 #[doc = "Indicates whether the unmanned aircraft is on the ground or in the air."]
8256 pub status: MavOdidStatus,
8257 #[doc = "Indicates the reference point for the height field."]
8258 pub height_reference: MavOdidHeightRef,
8259 #[doc = "The accuracy of the horizontal position."]
8260 pub horizontal_accuracy: MavOdidHorAcc,
8261 #[doc = "The accuracy of the vertical position."]
8262 pub vertical_accuracy: MavOdidVerAcc,
8263 #[doc = "The accuracy of the barometric altitude."]
8264 pub barometer_accuracy: MavOdidVerAcc,
8265 #[doc = "The accuracy of the horizontal and vertical speed."]
8266 pub speed_accuracy: MavOdidSpeedAcc,
8267 #[doc = "The accuracy of the timestamps."]
8268 pub timestamp_accuracy: MavOdidTimeAcc,
8269}
8270impl OPEN_DRONE_ID_LOCATION_DATA {
8271 pub const ENCODED_LEN: usize = 59usize;
8272 pub const DEFAULT: Self = Self {
8273 latitude: 0_i32,
8274 longitude: 0_i32,
8275 altitude_barometric: 0.0_f32,
8276 altitude_geodetic: 0.0_f32,
8277 height: 0.0_f32,
8278 timestamp: 0.0_f32,
8279 direction: 0_u16,
8280 speed_horizontal: 0_u16,
8281 speed_vertical: 0_i16,
8282 target_system: 0_u8,
8283 target_component: 0_u8,
8284 id_or_mac: [0_u8; 20usize],
8285 status: MavOdidStatus::DEFAULT,
8286 height_reference: MavOdidHeightRef::DEFAULT,
8287 horizontal_accuracy: MavOdidHorAcc::DEFAULT,
8288 vertical_accuracy: MavOdidVerAcc::DEFAULT,
8289 barometer_accuracy: MavOdidVerAcc::DEFAULT,
8290 speed_accuracy: MavOdidSpeedAcc::DEFAULT,
8291 timestamp_accuracy: MavOdidTimeAcc::DEFAULT,
8292 };
8293 #[cfg(feature = "arbitrary")]
8294 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8295 use arbitrary::{Arbitrary, Unstructured};
8296 let mut buf = [0u8; 1024];
8297 rng.fill_bytes(&mut buf);
8298 let mut unstructured = Unstructured::new(&buf);
8299 Self::arbitrary(&mut unstructured).unwrap_or_default()
8300 }
8301}
8302impl Default for OPEN_DRONE_ID_LOCATION_DATA {
8303 fn default() -> Self {
8304 Self::DEFAULT.clone()
8305 }
8306}
8307impl MessageData for OPEN_DRONE_ID_LOCATION_DATA {
8308 type Message = MavMessage;
8309 const ID: u32 = 12901u32;
8310 const NAME: &'static str = "OPEN_DRONE_ID_LOCATION";
8311 const EXTRA_CRC: u8 = 254u8;
8312 const ENCODED_LEN: usize = 59usize;
8313 fn deser(
8314 _version: MavlinkVersion,
8315 __input: &[u8],
8316 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8317 let avail_len = __input.len();
8318 let mut payload_buf = [0; Self::ENCODED_LEN];
8319 let mut buf = if avail_len < Self::ENCODED_LEN {
8320 payload_buf[0..avail_len].copy_from_slice(__input);
8321 Bytes::new(&payload_buf)
8322 } else {
8323 Bytes::new(__input)
8324 };
8325 let mut __struct = Self::default();
8326 __struct.latitude = buf.get_i32_le();
8327 __struct.longitude = buf.get_i32_le();
8328 __struct.altitude_barometric = buf.get_f32_le();
8329 __struct.altitude_geodetic = buf.get_f32_le();
8330 __struct.height = buf.get_f32_le();
8331 __struct.timestamp = buf.get_f32_le();
8332 __struct.direction = buf.get_u16_le();
8333 __struct.speed_horizontal = buf.get_u16_le();
8334 __struct.speed_vertical = buf.get_i16_le();
8335 __struct.target_system = buf.get_u8();
8336 __struct.target_component = buf.get_u8();
8337 for v in &mut __struct.id_or_mac {
8338 let val = buf.get_u8();
8339 *v = val;
8340 }
8341 let tmp = buf.get_u8();
8342 __struct.status =
8343 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8344 enum_type: "MavOdidStatus",
8345 value: tmp as u32,
8346 })?;
8347 let tmp = buf.get_u8();
8348 __struct.height_reference =
8349 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8350 enum_type: "MavOdidHeightRef",
8351 value: tmp as u32,
8352 })?;
8353 let tmp = buf.get_u8();
8354 __struct.horizontal_accuracy =
8355 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8356 enum_type: "MavOdidHorAcc",
8357 value: tmp as u32,
8358 })?;
8359 let tmp = buf.get_u8();
8360 __struct.vertical_accuracy =
8361 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8362 enum_type: "MavOdidVerAcc",
8363 value: tmp as u32,
8364 })?;
8365 let tmp = buf.get_u8();
8366 __struct.barometer_accuracy =
8367 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8368 enum_type: "MavOdidVerAcc",
8369 value: tmp as u32,
8370 })?;
8371 let tmp = buf.get_u8();
8372 __struct.speed_accuracy =
8373 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8374 enum_type: "MavOdidSpeedAcc",
8375 value: tmp as u32,
8376 })?;
8377 let tmp = buf.get_u8();
8378 __struct.timestamp_accuracy =
8379 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8380 enum_type: "MavOdidTimeAcc",
8381 value: tmp as u32,
8382 })?;
8383 Ok(__struct)
8384 }
8385 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8386 let mut __tmp = BytesMut::new(bytes);
8387 #[allow(clippy::absurd_extreme_comparisons)]
8388 #[allow(unused_comparisons)]
8389 if __tmp.remaining() < Self::ENCODED_LEN {
8390 panic!(
8391 "buffer is too small (need {} bytes, but got {})",
8392 Self::ENCODED_LEN,
8393 __tmp.remaining(),
8394 )
8395 }
8396 __tmp.put_i32_le(self.latitude);
8397 __tmp.put_i32_le(self.longitude);
8398 __tmp.put_f32_le(self.altitude_barometric);
8399 __tmp.put_f32_le(self.altitude_geodetic);
8400 __tmp.put_f32_le(self.height);
8401 __tmp.put_f32_le(self.timestamp);
8402 __tmp.put_u16_le(self.direction);
8403 __tmp.put_u16_le(self.speed_horizontal);
8404 __tmp.put_i16_le(self.speed_vertical);
8405 __tmp.put_u8(self.target_system);
8406 __tmp.put_u8(self.target_component);
8407 for val in &self.id_or_mac {
8408 __tmp.put_u8(*val);
8409 }
8410 __tmp.put_u8(self.status as u8);
8411 __tmp.put_u8(self.height_reference as u8);
8412 __tmp.put_u8(self.horizontal_accuracy as u8);
8413 __tmp.put_u8(self.vertical_accuracy as u8);
8414 __tmp.put_u8(self.barometer_accuracy as u8);
8415 __tmp.put_u8(self.speed_accuracy as u8);
8416 __tmp.put_u8(self.timestamp_accuracy as u8);
8417 if matches!(version, MavlinkVersion::V2) {
8418 let len = __tmp.len();
8419 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8420 } else {
8421 __tmp.len()
8422 }
8423 }
8424}
8425#[doc = "id: 277"]
8426#[doc = "Camera absolute thermal range. This can be streamed when the associated VIDEO_STREAM_STATUS `flag` field bit VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED is set, but a GCS may choose to only request it for the current active stream. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval (param3 indicates the stream id of the current camera, or 0 for all streams, param4 indicates the target camera_device_id for autopilot-attached cameras or 0 for MAVLink cameras)."]
8427#[derive(Debug, Clone, PartialEq)]
8428#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8429#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8430pub struct CAMERA_THERMAL_RANGE_DATA {
8431 #[doc = "Timestamp (time since system boot)."]
8432 pub time_boot_ms: u32,
8433 #[doc = "Temperature max."]
8434 pub max: f32,
8435 #[doc = "Temperature max point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
8436 pub max_point_x: f32,
8437 #[doc = "Temperature max point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
8438 pub max_point_y: f32,
8439 #[doc = "Temperature min."]
8440 pub min: f32,
8441 #[doc = "Temperature min point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
8442 pub min_point_x: f32,
8443 #[doc = "Temperature min point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
8444 pub min_point_y: f32,
8445 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
8446 pub stream_id: u8,
8447 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
8448 pub camera_device_id: u8,
8449}
8450impl CAMERA_THERMAL_RANGE_DATA {
8451 pub const ENCODED_LEN: usize = 30usize;
8452 pub const DEFAULT: Self = Self {
8453 time_boot_ms: 0_u32,
8454 max: 0.0_f32,
8455 max_point_x: 0.0_f32,
8456 max_point_y: 0.0_f32,
8457 min: 0.0_f32,
8458 min_point_x: 0.0_f32,
8459 min_point_y: 0.0_f32,
8460 stream_id: 0_u8,
8461 camera_device_id: 0_u8,
8462 };
8463 #[cfg(feature = "arbitrary")]
8464 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8465 use arbitrary::{Arbitrary, Unstructured};
8466 let mut buf = [0u8; 1024];
8467 rng.fill_bytes(&mut buf);
8468 let mut unstructured = Unstructured::new(&buf);
8469 Self::arbitrary(&mut unstructured).unwrap_or_default()
8470 }
8471}
8472impl Default for CAMERA_THERMAL_RANGE_DATA {
8473 fn default() -> Self {
8474 Self::DEFAULT.clone()
8475 }
8476}
8477impl MessageData for CAMERA_THERMAL_RANGE_DATA {
8478 type Message = MavMessage;
8479 const ID: u32 = 277u32;
8480 const NAME: &'static str = "CAMERA_THERMAL_RANGE";
8481 const EXTRA_CRC: u8 = 62u8;
8482 const ENCODED_LEN: usize = 30usize;
8483 fn deser(
8484 _version: MavlinkVersion,
8485 __input: &[u8],
8486 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8487 let avail_len = __input.len();
8488 let mut payload_buf = [0; Self::ENCODED_LEN];
8489 let mut buf = if avail_len < Self::ENCODED_LEN {
8490 payload_buf[0..avail_len].copy_from_slice(__input);
8491 Bytes::new(&payload_buf)
8492 } else {
8493 Bytes::new(__input)
8494 };
8495 let mut __struct = Self::default();
8496 __struct.time_boot_ms = buf.get_u32_le();
8497 __struct.max = buf.get_f32_le();
8498 __struct.max_point_x = buf.get_f32_le();
8499 __struct.max_point_y = buf.get_f32_le();
8500 __struct.min = buf.get_f32_le();
8501 __struct.min_point_x = buf.get_f32_le();
8502 __struct.min_point_y = buf.get_f32_le();
8503 __struct.stream_id = buf.get_u8();
8504 __struct.camera_device_id = buf.get_u8();
8505 Ok(__struct)
8506 }
8507 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8508 let mut __tmp = BytesMut::new(bytes);
8509 #[allow(clippy::absurd_extreme_comparisons)]
8510 #[allow(unused_comparisons)]
8511 if __tmp.remaining() < Self::ENCODED_LEN {
8512 panic!(
8513 "buffer is too small (need {} bytes, but got {})",
8514 Self::ENCODED_LEN,
8515 __tmp.remaining(),
8516 )
8517 }
8518 __tmp.put_u32_le(self.time_boot_ms);
8519 __tmp.put_f32_le(self.max);
8520 __tmp.put_f32_le(self.max_point_x);
8521 __tmp.put_f32_le(self.max_point_y);
8522 __tmp.put_f32_le(self.min);
8523 __tmp.put_f32_le(self.min_point_x);
8524 __tmp.put_f32_le(self.min_point_y);
8525 __tmp.put_u8(self.stream_id);
8526 __tmp.put_u8(self.camera_device_id);
8527 if matches!(version, MavlinkVersion::V2) {
8528 let len = __tmp.len();
8529 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8530 } else {
8531 __tmp.len()
8532 }
8533 }
8534}
8535#[doc = "id: 268"]
8536#[doc = "An ack for a LOGGING_DATA_ACKED message."]
8537#[derive(Debug, Clone, PartialEq)]
8538#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8539#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8540pub struct LOGGING_ACK_DATA {
8541 #[doc = "sequence number (must match the one in LOGGING_DATA_ACKED)"]
8542 pub sequence: u16,
8543 #[doc = "system ID of the target"]
8544 pub target_system: u8,
8545 #[doc = "component ID of the target"]
8546 pub target_component: u8,
8547}
8548impl LOGGING_ACK_DATA {
8549 pub const ENCODED_LEN: usize = 4usize;
8550 pub const DEFAULT: Self = Self {
8551 sequence: 0_u16,
8552 target_system: 0_u8,
8553 target_component: 0_u8,
8554 };
8555 #[cfg(feature = "arbitrary")]
8556 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8557 use arbitrary::{Arbitrary, Unstructured};
8558 let mut buf = [0u8; 1024];
8559 rng.fill_bytes(&mut buf);
8560 let mut unstructured = Unstructured::new(&buf);
8561 Self::arbitrary(&mut unstructured).unwrap_or_default()
8562 }
8563}
8564impl Default for LOGGING_ACK_DATA {
8565 fn default() -> Self {
8566 Self::DEFAULT.clone()
8567 }
8568}
8569impl MessageData for LOGGING_ACK_DATA {
8570 type Message = MavMessage;
8571 const ID: u32 = 268u32;
8572 const NAME: &'static str = "LOGGING_ACK";
8573 const EXTRA_CRC: u8 = 14u8;
8574 const ENCODED_LEN: usize = 4usize;
8575 fn deser(
8576 _version: MavlinkVersion,
8577 __input: &[u8],
8578 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8579 let avail_len = __input.len();
8580 let mut payload_buf = [0; Self::ENCODED_LEN];
8581 let mut buf = if avail_len < Self::ENCODED_LEN {
8582 payload_buf[0..avail_len].copy_from_slice(__input);
8583 Bytes::new(&payload_buf)
8584 } else {
8585 Bytes::new(__input)
8586 };
8587 let mut __struct = Self::default();
8588 __struct.sequence = buf.get_u16_le();
8589 __struct.target_system = buf.get_u8();
8590 __struct.target_component = buf.get_u8();
8591 Ok(__struct)
8592 }
8593 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8594 let mut __tmp = BytesMut::new(bytes);
8595 #[allow(clippy::absurd_extreme_comparisons)]
8596 #[allow(unused_comparisons)]
8597 if __tmp.remaining() < Self::ENCODED_LEN {
8598 panic!(
8599 "buffer is too small (need {} bytes, but got {})",
8600 Self::ENCODED_LEN,
8601 __tmp.remaining(),
8602 )
8603 }
8604 __tmp.put_u16_le(self.sequence);
8605 __tmp.put_u8(self.target_system);
8606 __tmp.put_u8(self.target_component);
8607 if matches!(version, MavlinkVersion::V2) {
8608 let len = __tmp.len();
8609 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8610 } else {
8611 __tmp.len()
8612 }
8613 }
8614}
8615#[doc = "id: 91"]
8616#[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to HIL_ACTUATOR_CONTROLS."]
8617#[derive(Debug, Clone, PartialEq)]
8618#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8619#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8620pub struct HIL_CONTROLS_DATA {
8621 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
8622 pub time_usec: u64,
8623 #[doc = "Control output -1 .. 1"]
8624 pub roll_ailerons: f32,
8625 #[doc = "Control output -1 .. 1"]
8626 pub pitch_elevator: f32,
8627 #[doc = "Control output -1 .. 1"]
8628 pub yaw_rudder: f32,
8629 #[doc = "Throttle 0 .. 1"]
8630 pub throttle: f32,
8631 #[doc = "Aux 1, -1 .. 1"]
8632 pub aux1: f32,
8633 #[doc = "Aux 2, -1 .. 1"]
8634 pub aux2: f32,
8635 #[doc = "Aux 3, -1 .. 1"]
8636 pub aux3: f32,
8637 #[doc = "Aux 4, -1 .. 1"]
8638 pub aux4: f32,
8639 #[doc = "System mode."]
8640 pub mode: MavMode,
8641 #[doc = "Navigation mode (MAV_NAV_MODE)"]
8642 pub nav_mode: u8,
8643}
8644impl HIL_CONTROLS_DATA {
8645 pub const ENCODED_LEN: usize = 42usize;
8646 pub const DEFAULT: Self = Self {
8647 time_usec: 0_u64,
8648 roll_ailerons: 0.0_f32,
8649 pitch_elevator: 0.0_f32,
8650 yaw_rudder: 0.0_f32,
8651 throttle: 0.0_f32,
8652 aux1: 0.0_f32,
8653 aux2: 0.0_f32,
8654 aux3: 0.0_f32,
8655 aux4: 0.0_f32,
8656 mode: MavMode::DEFAULT,
8657 nav_mode: 0_u8,
8658 };
8659 #[cfg(feature = "arbitrary")]
8660 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8661 use arbitrary::{Arbitrary, Unstructured};
8662 let mut buf = [0u8; 1024];
8663 rng.fill_bytes(&mut buf);
8664 let mut unstructured = Unstructured::new(&buf);
8665 Self::arbitrary(&mut unstructured).unwrap_or_default()
8666 }
8667}
8668impl Default for HIL_CONTROLS_DATA {
8669 fn default() -> Self {
8670 Self::DEFAULT.clone()
8671 }
8672}
8673impl MessageData for HIL_CONTROLS_DATA {
8674 type Message = MavMessage;
8675 const ID: u32 = 91u32;
8676 const NAME: &'static str = "HIL_CONTROLS";
8677 const EXTRA_CRC: u8 = 63u8;
8678 const ENCODED_LEN: usize = 42usize;
8679 fn deser(
8680 _version: MavlinkVersion,
8681 __input: &[u8],
8682 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8683 let avail_len = __input.len();
8684 let mut payload_buf = [0; Self::ENCODED_LEN];
8685 let mut buf = if avail_len < Self::ENCODED_LEN {
8686 payload_buf[0..avail_len].copy_from_slice(__input);
8687 Bytes::new(&payload_buf)
8688 } else {
8689 Bytes::new(__input)
8690 };
8691 let mut __struct = Self::default();
8692 __struct.time_usec = buf.get_u64_le();
8693 __struct.roll_ailerons = buf.get_f32_le();
8694 __struct.pitch_elevator = buf.get_f32_le();
8695 __struct.yaw_rudder = buf.get_f32_le();
8696 __struct.throttle = buf.get_f32_le();
8697 __struct.aux1 = buf.get_f32_le();
8698 __struct.aux2 = buf.get_f32_le();
8699 __struct.aux3 = buf.get_f32_le();
8700 __struct.aux4 = buf.get_f32_le();
8701 let tmp = buf.get_u8();
8702 __struct.mode =
8703 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8704 enum_type: "MavMode",
8705 value: tmp as u32,
8706 })?;
8707 __struct.nav_mode = buf.get_u8();
8708 Ok(__struct)
8709 }
8710 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8711 let mut __tmp = BytesMut::new(bytes);
8712 #[allow(clippy::absurd_extreme_comparisons)]
8713 #[allow(unused_comparisons)]
8714 if __tmp.remaining() < Self::ENCODED_LEN {
8715 panic!(
8716 "buffer is too small (need {} bytes, but got {})",
8717 Self::ENCODED_LEN,
8718 __tmp.remaining(),
8719 )
8720 }
8721 __tmp.put_u64_le(self.time_usec);
8722 __tmp.put_f32_le(self.roll_ailerons);
8723 __tmp.put_f32_le(self.pitch_elevator);
8724 __tmp.put_f32_le(self.yaw_rudder);
8725 __tmp.put_f32_le(self.throttle);
8726 __tmp.put_f32_le(self.aux1);
8727 __tmp.put_f32_le(self.aux2);
8728 __tmp.put_f32_le(self.aux3);
8729 __tmp.put_f32_le(self.aux4);
8730 __tmp.put_u8(self.mode as u8);
8731 __tmp.put_u8(self.nav_mode);
8732 if matches!(version, MavlinkVersion::V2) {
8733 let len = __tmp.len();
8734 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8735 } else {
8736 __tmp.len()
8737 }
8738 }
8739}
8740#[doc = "id: 373"]
8741#[doc = "Telemetry of power generation system. Alternator or mechanical generator."]
8742#[derive(Debug, Clone, PartialEq)]
8743#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8744#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8745pub struct GENERATOR_STATUS_DATA {
8746 #[doc = "Status flags."]
8747 pub status: MavGeneratorStatusFlag,
8748 #[doc = "Current into/out of battery. Positive for out. Negative for in. NaN: field not provided."]
8749 pub battery_current: f32,
8750 #[doc = "Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided"]
8751 pub load_current: f32,
8752 #[doc = "The power being generated. NaN: field not provided"]
8753 pub power_generated: f32,
8754 #[doc = "Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus."]
8755 pub bus_voltage: f32,
8756 #[doc = "The target battery current. Positive for out. Negative for in. NaN: field not provided"]
8757 pub bat_current_setpoint: f32,
8758 #[doc = "Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided."]
8759 pub runtime: u32,
8760 #[doc = "Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided."]
8761 pub time_until_maintenance: i32,
8762 #[doc = "Speed of electrical generator or alternator. UINT16_MAX: field not provided."]
8763 pub generator_speed: u16,
8764 #[doc = "The temperature of the rectifier or power converter. INT16_MAX: field not provided."]
8765 pub rectifier_temperature: i16,
8766 #[doc = "The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided."]
8767 pub generator_temperature: i16,
8768}
8769impl GENERATOR_STATUS_DATA {
8770 pub const ENCODED_LEN: usize = 42usize;
8771 pub const DEFAULT: Self = Self {
8772 status: MavGeneratorStatusFlag::DEFAULT,
8773 battery_current: 0.0_f32,
8774 load_current: 0.0_f32,
8775 power_generated: 0.0_f32,
8776 bus_voltage: 0.0_f32,
8777 bat_current_setpoint: 0.0_f32,
8778 runtime: 0_u32,
8779 time_until_maintenance: 0_i32,
8780 generator_speed: 0_u16,
8781 rectifier_temperature: 0_i16,
8782 generator_temperature: 0_i16,
8783 };
8784 #[cfg(feature = "arbitrary")]
8785 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8786 use arbitrary::{Arbitrary, Unstructured};
8787 let mut buf = [0u8; 1024];
8788 rng.fill_bytes(&mut buf);
8789 let mut unstructured = Unstructured::new(&buf);
8790 Self::arbitrary(&mut unstructured).unwrap_or_default()
8791 }
8792}
8793impl Default for GENERATOR_STATUS_DATA {
8794 fn default() -> Self {
8795 Self::DEFAULT.clone()
8796 }
8797}
8798impl MessageData for GENERATOR_STATUS_DATA {
8799 type Message = MavMessage;
8800 const ID: u32 = 373u32;
8801 const NAME: &'static str = "GENERATOR_STATUS";
8802 const EXTRA_CRC: u8 = 117u8;
8803 const ENCODED_LEN: usize = 42usize;
8804 fn deser(
8805 _version: MavlinkVersion,
8806 __input: &[u8],
8807 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8808 let avail_len = __input.len();
8809 let mut payload_buf = [0; Self::ENCODED_LEN];
8810 let mut buf = if avail_len < Self::ENCODED_LEN {
8811 payload_buf[0..avail_len].copy_from_slice(__input);
8812 Bytes::new(&payload_buf)
8813 } else {
8814 Bytes::new(__input)
8815 };
8816 let mut __struct = Self::default();
8817 let tmp = buf.get_u64_le();
8818 __struct.status = MavGeneratorStatusFlag::from_bits(
8819 tmp & MavGeneratorStatusFlag::all().bits(),
8820 )
8821 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
8822 flag_type: "MavGeneratorStatusFlag",
8823 value: tmp as u32,
8824 })?;
8825 __struct.battery_current = buf.get_f32_le();
8826 __struct.load_current = buf.get_f32_le();
8827 __struct.power_generated = buf.get_f32_le();
8828 __struct.bus_voltage = buf.get_f32_le();
8829 __struct.bat_current_setpoint = buf.get_f32_le();
8830 __struct.runtime = buf.get_u32_le();
8831 __struct.time_until_maintenance = buf.get_i32_le();
8832 __struct.generator_speed = buf.get_u16_le();
8833 __struct.rectifier_temperature = buf.get_i16_le();
8834 __struct.generator_temperature = buf.get_i16_le();
8835 Ok(__struct)
8836 }
8837 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8838 let mut __tmp = BytesMut::new(bytes);
8839 #[allow(clippy::absurd_extreme_comparisons)]
8840 #[allow(unused_comparisons)]
8841 if __tmp.remaining() < Self::ENCODED_LEN {
8842 panic!(
8843 "buffer is too small (need {} bytes, but got {})",
8844 Self::ENCODED_LEN,
8845 __tmp.remaining(),
8846 )
8847 }
8848 __tmp.put_u64_le(self.status.bits());
8849 __tmp.put_f32_le(self.battery_current);
8850 __tmp.put_f32_le(self.load_current);
8851 __tmp.put_f32_le(self.power_generated);
8852 __tmp.put_f32_le(self.bus_voltage);
8853 __tmp.put_f32_le(self.bat_current_setpoint);
8854 __tmp.put_u32_le(self.runtime);
8855 __tmp.put_i32_le(self.time_until_maintenance);
8856 __tmp.put_u16_le(self.generator_speed);
8857 __tmp.put_i16_le(self.rectifier_temperature);
8858 __tmp.put_i16_le(self.generator_temperature);
8859 if matches!(version, MavlinkVersion::V2) {
8860 let len = __tmp.len();
8861 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8862 } else {
8863 __tmp.len()
8864 }
8865 }
8866}
8867#[doc = "id: 144"]
8868#[doc = "Current motion information from a designated system."]
8869#[derive(Debug, Clone, PartialEq)]
8870#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8871#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8872pub struct FOLLOW_TARGET_DATA {
8873 #[doc = "Timestamp (time since system boot)."]
8874 pub timestamp: u64,
8875 #[doc = "button states or switches of a tracker device"]
8876 pub custom_state: u64,
8877 #[doc = "Latitude (WGS84)"]
8878 pub lat: i32,
8879 #[doc = "Longitude (WGS84)"]
8880 pub lon: i32,
8881 #[doc = "Altitude (MSL)"]
8882 pub alt: f32,
8883 #[doc = "target velocity (0,0,0) for unknown"]
8884 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8885 pub vel: [f32; 3],
8886 #[doc = "linear target acceleration (0,0,0) for unknown"]
8887 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8888 pub acc: [f32; 3],
8889 #[doc = "(0 0 0 0 for unknown)"]
8890 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8891 pub attitude_q: [f32; 4],
8892 #[doc = "(0 0 0 for unknown)"]
8893 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8894 pub rates: [f32; 3],
8895 #[doc = "eph epv"]
8896 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8897 pub position_cov: [f32; 3],
8898 #[doc = "bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)"]
8899 pub est_capabilities: u8,
8900}
8901impl FOLLOW_TARGET_DATA {
8902 pub const ENCODED_LEN: usize = 93usize;
8903 pub const DEFAULT: Self = Self {
8904 timestamp: 0_u64,
8905 custom_state: 0_u64,
8906 lat: 0_i32,
8907 lon: 0_i32,
8908 alt: 0.0_f32,
8909 vel: [0.0_f32; 3usize],
8910 acc: [0.0_f32; 3usize],
8911 attitude_q: [0.0_f32; 4usize],
8912 rates: [0.0_f32; 3usize],
8913 position_cov: [0.0_f32; 3usize],
8914 est_capabilities: 0_u8,
8915 };
8916 #[cfg(feature = "arbitrary")]
8917 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8918 use arbitrary::{Arbitrary, Unstructured};
8919 let mut buf = [0u8; 1024];
8920 rng.fill_bytes(&mut buf);
8921 let mut unstructured = Unstructured::new(&buf);
8922 Self::arbitrary(&mut unstructured).unwrap_or_default()
8923 }
8924}
8925impl Default for FOLLOW_TARGET_DATA {
8926 fn default() -> Self {
8927 Self::DEFAULT.clone()
8928 }
8929}
8930impl MessageData for FOLLOW_TARGET_DATA {
8931 type Message = MavMessage;
8932 const ID: u32 = 144u32;
8933 const NAME: &'static str = "FOLLOW_TARGET";
8934 const EXTRA_CRC: u8 = 127u8;
8935 const ENCODED_LEN: usize = 93usize;
8936 fn deser(
8937 _version: MavlinkVersion,
8938 __input: &[u8],
8939 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8940 let avail_len = __input.len();
8941 let mut payload_buf = [0; Self::ENCODED_LEN];
8942 let mut buf = if avail_len < Self::ENCODED_LEN {
8943 payload_buf[0..avail_len].copy_from_slice(__input);
8944 Bytes::new(&payload_buf)
8945 } else {
8946 Bytes::new(__input)
8947 };
8948 let mut __struct = Self::default();
8949 __struct.timestamp = buf.get_u64_le();
8950 __struct.custom_state = buf.get_u64_le();
8951 __struct.lat = buf.get_i32_le();
8952 __struct.lon = buf.get_i32_le();
8953 __struct.alt = buf.get_f32_le();
8954 for v in &mut __struct.vel {
8955 let val = buf.get_f32_le();
8956 *v = val;
8957 }
8958 for v in &mut __struct.acc {
8959 let val = buf.get_f32_le();
8960 *v = val;
8961 }
8962 for v in &mut __struct.attitude_q {
8963 let val = buf.get_f32_le();
8964 *v = val;
8965 }
8966 for v in &mut __struct.rates {
8967 let val = buf.get_f32_le();
8968 *v = val;
8969 }
8970 for v in &mut __struct.position_cov {
8971 let val = buf.get_f32_le();
8972 *v = val;
8973 }
8974 __struct.est_capabilities = buf.get_u8();
8975 Ok(__struct)
8976 }
8977 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8978 let mut __tmp = BytesMut::new(bytes);
8979 #[allow(clippy::absurd_extreme_comparisons)]
8980 #[allow(unused_comparisons)]
8981 if __tmp.remaining() < Self::ENCODED_LEN {
8982 panic!(
8983 "buffer is too small (need {} bytes, but got {})",
8984 Self::ENCODED_LEN,
8985 __tmp.remaining(),
8986 )
8987 }
8988 __tmp.put_u64_le(self.timestamp);
8989 __tmp.put_u64_le(self.custom_state);
8990 __tmp.put_i32_le(self.lat);
8991 __tmp.put_i32_le(self.lon);
8992 __tmp.put_f32_le(self.alt);
8993 for val in &self.vel {
8994 __tmp.put_f32_le(*val);
8995 }
8996 for val in &self.acc {
8997 __tmp.put_f32_le(*val);
8998 }
8999 for val in &self.attitude_q {
9000 __tmp.put_f32_le(*val);
9001 }
9002 for val in &self.rates {
9003 __tmp.put_f32_le(*val);
9004 }
9005 for val in &self.position_cov {
9006 __tmp.put_f32_le(*val);
9007 }
9008 __tmp.put_u8(self.est_capabilities);
9009 if matches!(version, MavlinkVersion::V2) {
9010 let len = __tmp.len();
9011 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9012 } else {
9013 __tmp.len()
9014 }
9015 }
9016}
9017#[doc = "id: 104"]
9018#[doc = "Global position estimate from a Vicon motion system source."]
9019#[derive(Debug, Clone, PartialEq)]
9020#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9021#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9022pub struct VICON_POSITION_ESTIMATE_DATA {
9023 #[doc = "Timestamp (UNIX time or time since system boot)"]
9024 pub usec: u64,
9025 #[doc = "Global X position"]
9026 pub x: f32,
9027 #[doc = "Global Y position"]
9028 pub y: f32,
9029 #[doc = "Global Z position"]
9030 pub z: f32,
9031 #[doc = "Roll angle"]
9032 pub roll: f32,
9033 #[doc = "Pitch angle"]
9034 pub pitch: f32,
9035 #[doc = "Yaw angle"]
9036 pub yaw: f32,
9037 #[doc = "Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
9038 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9039 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9040 pub covariance: [f32; 21],
9041}
9042impl VICON_POSITION_ESTIMATE_DATA {
9043 pub const ENCODED_LEN: usize = 116usize;
9044 pub const DEFAULT: Self = Self {
9045 usec: 0_u64,
9046 x: 0.0_f32,
9047 y: 0.0_f32,
9048 z: 0.0_f32,
9049 roll: 0.0_f32,
9050 pitch: 0.0_f32,
9051 yaw: 0.0_f32,
9052 covariance: [0.0_f32; 21usize],
9053 };
9054 #[cfg(feature = "arbitrary")]
9055 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9056 use arbitrary::{Arbitrary, Unstructured};
9057 let mut buf = [0u8; 1024];
9058 rng.fill_bytes(&mut buf);
9059 let mut unstructured = Unstructured::new(&buf);
9060 Self::arbitrary(&mut unstructured).unwrap_or_default()
9061 }
9062}
9063impl Default for VICON_POSITION_ESTIMATE_DATA {
9064 fn default() -> Self {
9065 Self::DEFAULT.clone()
9066 }
9067}
9068impl MessageData for VICON_POSITION_ESTIMATE_DATA {
9069 type Message = MavMessage;
9070 const ID: u32 = 104u32;
9071 const NAME: &'static str = "VICON_POSITION_ESTIMATE";
9072 const EXTRA_CRC: u8 = 56u8;
9073 const ENCODED_LEN: usize = 116usize;
9074 fn deser(
9075 _version: MavlinkVersion,
9076 __input: &[u8],
9077 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9078 let avail_len = __input.len();
9079 let mut payload_buf = [0; Self::ENCODED_LEN];
9080 let mut buf = if avail_len < Self::ENCODED_LEN {
9081 payload_buf[0..avail_len].copy_from_slice(__input);
9082 Bytes::new(&payload_buf)
9083 } else {
9084 Bytes::new(__input)
9085 };
9086 let mut __struct = Self::default();
9087 __struct.usec = buf.get_u64_le();
9088 __struct.x = buf.get_f32_le();
9089 __struct.y = buf.get_f32_le();
9090 __struct.z = buf.get_f32_le();
9091 __struct.roll = buf.get_f32_le();
9092 __struct.pitch = buf.get_f32_le();
9093 __struct.yaw = buf.get_f32_le();
9094 for v in &mut __struct.covariance {
9095 let val = buf.get_f32_le();
9096 *v = val;
9097 }
9098 Ok(__struct)
9099 }
9100 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9101 let mut __tmp = BytesMut::new(bytes);
9102 #[allow(clippy::absurd_extreme_comparisons)]
9103 #[allow(unused_comparisons)]
9104 if __tmp.remaining() < Self::ENCODED_LEN {
9105 panic!(
9106 "buffer is too small (need {} bytes, but got {})",
9107 Self::ENCODED_LEN,
9108 __tmp.remaining(),
9109 )
9110 }
9111 __tmp.put_u64_le(self.usec);
9112 __tmp.put_f32_le(self.x);
9113 __tmp.put_f32_le(self.y);
9114 __tmp.put_f32_le(self.z);
9115 __tmp.put_f32_le(self.roll);
9116 __tmp.put_f32_le(self.pitch);
9117 __tmp.put_f32_le(self.yaw);
9118 for val in &self.covariance {
9119 __tmp.put_f32_le(*val);
9120 }
9121 if matches!(version, MavlinkVersion::V2) {
9122 let len = __tmp.len();
9123 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9124 } else {
9125 __tmp.len()
9126 }
9127 }
9128}
9129#[doc = "id: 246"]
9130#[doc = "The location and information of an ADSB vehicle."]
9131#[derive(Debug, Clone, PartialEq)]
9132#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9133#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9134pub struct ADSB_VEHICLE_DATA {
9135 #[doc = "ICAO address"]
9136 pub ICAO_address: u32,
9137 #[doc = "Latitude"]
9138 pub lat: i32,
9139 #[doc = "Longitude"]
9140 pub lon: i32,
9141 #[doc = "Altitude(ASL)"]
9142 pub altitude: i32,
9143 #[doc = "Course over ground"]
9144 pub heading: u16,
9145 #[doc = "The horizontal velocity"]
9146 pub hor_velocity: u16,
9147 #[doc = "The vertical velocity. Positive is up"]
9148 pub ver_velocity: i16,
9149 #[doc = "Bitmap to indicate various statuses including valid data fields"]
9150 pub flags: AdsbFlags,
9151 #[doc = "Squawk code. Note that the code is in decimal: e.g. 7700 (general emergency) is encoded as binary 0b0001_1110_0001_0100, not(!) as 0b0000_111_111_000_000"]
9152 pub squawk: u16,
9153 #[doc = "ADSB altitude type."]
9154 pub altitude_type: AdsbAltitudeType,
9155 #[doc = "The callsign, 8+null"]
9156 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9157 pub callsign: [u8; 9],
9158 #[doc = "ADSB emitter type."]
9159 pub emitter_type: AdsbEmitterType,
9160 #[doc = "Time since last communication in seconds"]
9161 pub tslc: u8,
9162}
9163impl ADSB_VEHICLE_DATA {
9164 pub const ENCODED_LEN: usize = 38usize;
9165 pub const DEFAULT: Self = Self {
9166 ICAO_address: 0_u32,
9167 lat: 0_i32,
9168 lon: 0_i32,
9169 altitude: 0_i32,
9170 heading: 0_u16,
9171 hor_velocity: 0_u16,
9172 ver_velocity: 0_i16,
9173 flags: AdsbFlags::DEFAULT,
9174 squawk: 0_u16,
9175 altitude_type: AdsbAltitudeType::DEFAULT,
9176 callsign: [0_u8; 9usize],
9177 emitter_type: AdsbEmitterType::DEFAULT,
9178 tslc: 0_u8,
9179 };
9180 #[cfg(feature = "arbitrary")]
9181 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9182 use arbitrary::{Arbitrary, Unstructured};
9183 let mut buf = [0u8; 1024];
9184 rng.fill_bytes(&mut buf);
9185 let mut unstructured = Unstructured::new(&buf);
9186 Self::arbitrary(&mut unstructured).unwrap_or_default()
9187 }
9188}
9189impl Default for ADSB_VEHICLE_DATA {
9190 fn default() -> Self {
9191 Self::DEFAULT.clone()
9192 }
9193}
9194impl MessageData for ADSB_VEHICLE_DATA {
9195 type Message = MavMessage;
9196 const ID: u32 = 246u32;
9197 const NAME: &'static str = "ADSB_VEHICLE";
9198 const EXTRA_CRC: u8 = 184u8;
9199 const ENCODED_LEN: usize = 38usize;
9200 fn deser(
9201 _version: MavlinkVersion,
9202 __input: &[u8],
9203 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9204 let avail_len = __input.len();
9205 let mut payload_buf = [0; Self::ENCODED_LEN];
9206 let mut buf = if avail_len < Self::ENCODED_LEN {
9207 payload_buf[0..avail_len].copy_from_slice(__input);
9208 Bytes::new(&payload_buf)
9209 } else {
9210 Bytes::new(__input)
9211 };
9212 let mut __struct = Self::default();
9213 __struct.ICAO_address = buf.get_u32_le();
9214 __struct.lat = buf.get_i32_le();
9215 __struct.lon = buf.get_i32_le();
9216 __struct.altitude = buf.get_i32_le();
9217 __struct.heading = buf.get_u16_le();
9218 __struct.hor_velocity = buf.get_u16_le();
9219 __struct.ver_velocity = buf.get_i16_le();
9220 let tmp = buf.get_u16_le();
9221 __struct.flags = AdsbFlags::from_bits(tmp & AdsbFlags::all().bits()).ok_or(
9222 ::mavlink_core::error::ParserError::InvalidFlag {
9223 flag_type: "AdsbFlags",
9224 value: tmp as u32,
9225 },
9226 )?;
9227 __struct.squawk = buf.get_u16_le();
9228 let tmp = buf.get_u8();
9229 __struct.altitude_type =
9230 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9231 enum_type: "AdsbAltitudeType",
9232 value: tmp as u32,
9233 })?;
9234 for v in &mut __struct.callsign {
9235 let val = buf.get_u8();
9236 *v = val;
9237 }
9238 let tmp = buf.get_u8();
9239 __struct.emitter_type =
9240 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9241 enum_type: "AdsbEmitterType",
9242 value: tmp as u32,
9243 })?;
9244 __struct.tslc = buf.get_u8();
9245 Ok(__struct)
9246 }
9247 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9248 let mut __tmp = BytesMut::new(bytes);
9249 #[allow(clippy::absurd_extreme_comparisons)]
9250 #[allow(unused_comparisons)]
9251 if __tmp.remaining() < Self::ENCODED_LEN {
9252 panic!(
9253 "buffer is too small (need {} bytes, but got {})",
9254 Self::ENCODED_LEN,
9255 __tmp.remaining(),
9256 )
9257 }
9258 __tmp.put_u32_le(self.ICAO_address);
9259 __tmp.put_i32_le(self.lat);
9260 __tmp.put_i32_le(self.lon);
9261 __tmp.put_i32_le(self.altitude);
9262 __tmp.put_u16_le(self.heading);
9263 __tmp.put_u16_le(self.hor_velocity);
9264 __tmp.put_i16_le(self.ver_velocity);
9265 __tmp.put_u16_le(self.flags.bits());
9266 __tmp.put_u16_le(self.squawk);
9267 __tmp.put_u8(self.altitude_type as u8);
9268 for val in &self.callsign {
9269 __tmp.put_u8(*val);
9270 }
9271 __tmp.put_u8(self.emitter_type as u8);
9272 __tmp.put_u8(self.tslc);
9273 if matches!(version, MavlinkVersion::V2) {
9274 let len = __tmp.len();
9275 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9276 } else {
9277 __tmp.len()
9278 }
9279 }
9280}
9281#[doc = "id: 283"]
9282#[doc = "Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc.."]
9283#[derive(Debug, Clone, PartialEq)]
9284#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9285#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9286pub struct GIMBAL_DEVICE_INFORMATION_DATA {
9287 #[doc = "UID of gimbal hardware (0 if unknown)."]
9288 pub uid: u64,
9289 #[doc = "Timestamp (time since system boot)."]
9290 pub time_boot_ms: u32,
9291 #[doc = "0xff)."]
9292 pub firmware_version: u32,
9293 #[doc = "0xff)."]
9294 pub hardware_version: u32,
9295 #[doc = "Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown."]
9296 pub roll_min: f32,
9297 #[doc = "Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown."]
9298 pub roll_max: f32,
9299 #[doc = "Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown."]
9300 pub pitch_min: f32,
9301 #[doc = "Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown."]
9302 pub pitch_max: f32,
9303 #[doc = "Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown."]
9304 pub yaw_min: f32,
9305 #[doc = "Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown."]
9306 pub yaw_max: f32,
9307 #[doc = "Bitmap of gimbal capability flags."]
9308 pub cap_flags: GimbalDeviceCapFlags,
9309 #[doc = "Bitmap for use for gimbal-specific capability flags."]
9310 pub custom_cap_flags: u16,
9311 #[doc = "Name of the gimbal vendor."]
9312 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9313 pub vendor_name: [u8; 32],
9314 #[doc = "Name of the gimbal model."]
9315 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9316 pub model_name: [u8; 32],
9317 #[doc = "Custom name of the gimbal given to it by the user."]
9318 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9319 pub custom_name: [u8; 32],
9320 #[doc = "This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0."]
9321 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9322 pub gimbal_device_id: u8,
9323}
9324impl GIMBAL_DEVICE_INFORMATION_DATA {
9325 pub const ENCODED_LEN: usize = 145usize;
9326 pub const DEFAULT: Self = Self {
9327 uid: 0_u64,
9328 time_boot_ms: 0_u32,
9329 firmware_version: 0_u32,
9330 hardware_version: 0_u32,
9331 roll_min: 0.0_f32,
9332 roll_max: 0.0_f32,
9333 pitch_min: 0.0_f32,
9334 pitch_max: 0.0_f32,
9335 yaw_min: 0.0_f32,
9336 yaw_max: 0.0_f32,
9337 cap_flags: GimbalDeviceCapFlags::DEFAULT,
9338 custom_cap_flags: 0_u16,
9339 vendor_name: [0_u8; 32usize],
9340 model_name: [0_u8; 32usize],
9341 custom_name: [0_u8; 32usize],
9342 gimbal_device_id: 0_u8,
9343 };
9344 #[cfg(feature = "arbitrary")]
9345 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9346 use arbitrary::{Arbitrary, Unstructured};
9347 let mut buf = [0u8; 1024];
9348 rng.fill_bytes(&mut buf);
9349 let mut unstructured = Unstructured::new(&buf);
9350 Self::arbitrary(&mut unstructured).unwrap_or_default()
9351 }
9352}
9353impl Default for GIMBAL_DEVICE_INFORMATION_DATA {
9354 fn default() -> Self {
9355 Self::DEFAULT.clone()
9356 }
9357}
9358impl MessageData for GIMBAL_DEVICE_INFORMATION_DATA {
9359 type Message = MavMessage;
9360 const ID: u32 = 283u32;
9361 const NAME: &'static str = "GIMBAL_DEVICE_INFORMATION";
9362 const EXTRA_CRC: u8 = 74u8;
9363 const ENCODED_LEN: usize = 145usize;
9364 fn deser(
9365 _version: MavlinkVersion,
9366 __input: &[u8],
9367 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9368 let avail_len = __input.len();
9369 let mut payload_buf = [0; Self::ENCODED_LEN];
9370 let mut buf = if avail_len < Self::ENCODED_LEN {
9371 payload_buf[0..avail_len].copy_from_slice(__input);
9372 Bytes::new(&payload_buf)
9373 } else {
9374 Bytes::new(__input)
9375 };
9376 let mut __struct = Self::default();
9377 __struct.uid = buf.get_u64_le();
9378 __struct.time_boot_ms = buf.get_u32_le();
9379 __struct.firmware_version = buf.get_u32_le();
9380 __struct.hardware_version = buf.get_u32_le();
9381 __struct.roll_min = buf.get_f32_le();
9382 __struct.roll_max = buf.get_f32_le();
9383 __struct.pitch_min = buf.get_f32_le();
9384 __struct.pitch_max = buf.get_f32_le();
9385 __struct.yaw_min = buf.get_f32_le();
9386 __struct.yaw_max = buf.get_f32_le();
9387 let tmp = buf.get_u16_le();
9388 __struct.cap_flags = GimbalDeviceCapFlags::from_bits(
9389 tmp & GimbalDeviceCapFlags::all().bits(),
9390 )
9391 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
9392 flag_type: "GimbalDeviceCapFlags",
9393 value: tmp as u32,
9394 })?;
9395 __struct.custom_cap_flags = buf.get_u16_le();
9396 for v in &mut __struct.vendor_name {
9397 let val = buf.get_u8();
9398 *v = val;
9399 }
9400 for v in &mut __struct.model_name {
9401 let val = buf.get_u8();
9402 *v = val;
9403 }
9404 for v in &mut __struct.custom_name {
9405 let val = buf.get_u8();
9406 *v = val;
9407 }
9408 __struct.gimbal_device_id = buf.get_u8();
9409 Ok(__struct)
9410 }
9411 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9412 let mut __tmp = BytesMut::new(bytes);
9413 #[allow(clippy::absurd_extreme_comparisons)]
9414 #[allow(unused_comparisons)]
9415 if __tmp.remaining() < Self::ENCODED_LEN {
9416 panic!(
9417 "buffer is too small (need {} bytes, but got {})",
9418 Self::ENCODED_LEN,
9419 __tmp.remaining(),
9420 )
9421 }
9422 __tmp.put_u64_le(self.uid);
9423 __tmp.put_u32_le(self.time_boot_ms);
9424 __tmp.put_u32_le(self.firmware_version);
9425 __tmp.put_u32_le(self.hardware_version);
9426 __tmp.put_f32_le(self.roll_min);
9427 __tmp.put_f32_le(self.roll_max);
9428 __tmp.put_f32_le(self.pitch_min);
9429 __tmp.put_f32_le(self.pitch_max);
9430 __tmp.put_f32_le(self.yaw_min);
9431 __tmp.put_f32_le(self.yaw_max);
9432 __tmp.put_u16_le(self.cap_flags.bits());
9433 __tmp.put_u16_le(self.custom_cap_flags);
9434 for val in &self.vendor_name {
9435 __tmp.put_u8(*val);
9436 }
9437 for val in &self.model_name {
9438 __tmp.put_u8(*val);
9439 }
9440 for val in &self.custom_name {
9441 __tmp.put_u8(*val);
9442 }
9443 __tmp.put_u8(self.gimbal_device_id);
9444 if matches!(version, MavlinkVersion::V2) {
9445 let len = __tmp.len();
9446 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9447 } else {
9448 __tmp.len()
9449 }
9450 }
9451}
9452#[doc = "id: 10004"]
9453#[doc = "Aircraft Registration."]
9454#[derive(Debug, Clone, PartialEq)]
9455#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9456#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9457pub struct UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA {
9458 #[doc = "Aircraft Registration (ASCII string A-Z, 0-9 only), e.g. \"N8644B \". Trailing spaces (0x20) only. This is null-terminated."]
9459 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9460 pub registration: [u8; 9],
9461}
9462impl UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA {
9463 pub const ENCODED_LEN: usize = 9usize;
9464 pub const DEFAULT: Self = Self {
9465 registration: [0_u8; 9usize],
9466 };
9467 #[cfg(feature = "arbitrary")]
9468 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9469 use arbitrary::{Arbitrary, Unstructured};
9470 let mut buf = [0u8; 1024];
9471 rng.fill_bytes(&mut buf);
9472 let mut unstructured = Unstructured::new(&buf);
9473 Self::arbitrary(&mut unstructured).unwrap_or_default()
9474 }
9475}
9476impl Default for UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA {
9477 fn default() -> Self {
9478 Self::DEFAULT.clone()
9479 }
9480}
9481impl MessageData for UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA {
9482 type Message = MavMessage;
9483 const ID: u32 = 10004u32;
9484 const NAME: &'static str = "UAVIONIX_ADSB_OUT_CFG_REGISTRATION";
9485 const EXTRA_CRC: u8 = 133u8;
9486 const ENCODED_LEN: usize = 9usize;
9487 fn deser(
9488 _version: MavlinkVersion,
9489 __input: &[u8],
9490 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9491 let avail_len = __input.len();
9492 let mut payload_buf = [0; Self::ENCODED_LEN];
9493 let mut buf = if avail_len < Self::ENCODED_LEN {
9494 payload_buf[0..avail_len].copy_from_slice(__input);
9495 Bytes::new(&payload_buf)
9496 } else {
9497 Bytes::new(__input)
9498 };
9499 let mut __struct = Self::default();
9500 for v in &mut __struct.registration {
9501 let val = buf.get_u8();
9502 *v = val;
9503 }
9504 Ok(__struct)
9505 }
9506 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9507 let mut __tmp = BytesMut::new(bytes);
9508 #[allow(clippy::absurd_extreme_comparisons)]
9509 #[allow(unused_comparisons)]
9510 if __tmp.remaining() < Self::ENCODED_LEN {
9511 panic!(
9512 "buffer is too small (need {} bytes, but got {})",
9513 Self::ENCODED_LEN,
9514 __tmp.remaining(),
9515 )
9516 }
9517 for val in &self.registration {
9518 __tmp.put_u8(*val);
9519 }
9520 if matches!(version, MavlinkVersion::V2) {
9521 let len = __tmp.len();
9522 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9523 } else {
9524 __tmp.len()
9525 }
9526 }
9527}
9528#[doc = "id: 370"]
9529#[doc = "Smart Battery information (static/infrequent update). Use for updates from: smart battery to flight stack, flight stack to GCS. Use BATTERY_STATUS for the frequent battery updates."]
9530#[derive(Debug, Clone, PartialEq)]
9531#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9532#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9533pub struct SMART_BATTERY_INFO_DATA {
9534 #[doc = "Capacity when full according to manufacturer, -1: field not provided."]
9535 pub capacity_full_specification: i32,
9536 #[doc = "Capacity when full (accounting for battery degradation), -1: field not provided."]
9537 pub capacity_full: i32,
9538 #[doc = "Charge/discharge cycle count. UINT16_MAX: field not provided."]
9539 pub cycle_count: u16,
9540 #[doc = "Battery weight. 0: field not provided."]
9541 pub weight: u16,
9542 #[doc = "Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value."]
9543 pub discharge_minimum_voltage: u16,
9544 #[doc = "Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value."]
9545 pub charging_minimum_voltage: u16,
9546 #[doc = "Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value."]
9547 pub resting_minimum_voltage: u16,
9548 #[doc = "Battery ID"]
9549 pub id: u8,
9550 #[doc = "Function of the battery"]
9551 pub battery_function: MavBatteryFunction,
9552 #[doc = "Type (chemistry) of the battery"]
9553 pub mavtype: MavBatteryType,
9554 #[doc = "Serial number in ASCII characters, 0 terminated. All 0: field not provided."]
9555 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9556 pub serial_number: [u8; 16],
9557 #[doc = "Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore."]
9558 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9559 pub device_name: [u8; 50],
9560 #[doc = "Maximum per-cell voltage when charged. 0: field not provided."]
9561 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9562 pub charging_maximum_voltage: u16,
9563 #[doc = "Number of battery cells in series. 0: field not provided."]
9564 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9565 pub cells_in_series: u8,
9566 #[doc = "Maximum pack discharge current. 0: field not provided."]
9567 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9568 pub discharge_maximum_current: u32,
9569 #[doc = "Maximum pack discharge burst current. 0: field not provided."]
9570 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9571 pub discharge_maximum_burst_current: u32,
9572 #[doc = "Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided."]
9573 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9574 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9575 pub manufacture_date: [u8; 11],
9576}
9577impl SMART_BATTERY_INFO_DATA {
9578 pub const ENCODED_LEN: usize = 109usize;
9579 pub const DEFAULT: Self = Self {
9580 capacity_full_specification: 0_i32,
9581 capacity_full: 0_i32,
9582 cycle_count: 0_u16,
9583 weight: 0_u16,
9584 discharge_minimum_voltage: 0_u16,
9585 charging_minimum_voltage: 0_u16,
9586 resting_minimum_voltage: 0_u16,
9587 id: 0_u8,
9588 battery_function: MavBatteryFunction::DEFAULT,
9589 mavtype: MavBatteryType::DEFAULT,
9590 serial_number: [0_u8; 16usize],
9591 device_name: [0_u8; 50usize],
9592 charging_maximum_voltage: 0_u16,
9593 cells_in_series: 0_u8,
9594 discharge_maximum_current: 0_u32,
9595 discharge_maximum_burst_current: 0_u32,
9596 manufacture_date: [0_u8; 11usize],
9597 };
9598 #[cfg(feature = "arbitrary")]
9599 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9600 use arbitrary::{Arbitrary, Unstructured};
9601 let mut buf = [0u8; 1024];
9602 rng.fill_bytes(&mut buf);
9603 let mut unstructured = Unstructured::new(&buf);
9604 Self::arbitrary(&mut unstructured).unwrap_or_default()
9605 }
9606}
9607impl Default for SMART_BATTERY_INFO_DATA {
9608 fn default() -> Self {
9609 Self::DEFAULT.clone()
9610 }
9611}
9612impl MessageData for SMART_BATTERY_INFO_DATA {
9613 type Message = MavMessage;
9614 const ID: u32 = 370u32;
9615 const NAME: &'static str = "SMART_BATTERY_INFO";
9616 const EXTRA_CRC: u8 = 75u8;
9617 const ENCODED_LEN: usize = 109usize;
9618 fn deser(
9619 _version: MavlinkVersion,
9620 __input: &[u8],
9621 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9622 let avail_len = __input.len();
9623 let mut payload_buf = [0; Self::ENCODED_LEN];
9624 let mut buf = if avail_len < Self::ENCODED_LEN {
9625 payload_buf[0..avail_len].copy_from_slice(__input);
9626 Bytes::new(&payload_buf)
9627 } else {
9628 Bytes::new(__input)
9629 };
9630 let mut __struct = Self::default();
9631 __struct.capacity_full_specification = buf.get_i32_le();
9632 __struct.capacity_full = buf.get_i32_le();
9633 __struct.cycle_count = buf.get_u16_le();
9634 __struct.weight = buf.get_u16_le();
9635 __struct.discharge_minimum_voltage = buf.get_u16_le();
9636 __struct.charging_minimum_voltage = buf.get_u16_le();
9637 __struct.resting_minimum_voltage = buf.get_u16_le();
9638 __struct.id = buf.get_u8();
9639 let tmp = buf.get_u8();
9640 __struct.battery_function =
9641 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9642 enum_type: "MavBatteryFunction",
9643 value: tmp as u32,
9644 })?;
9645 let tmp = buf.get_u8();
9646 __struct.mavtype =
9647 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9648 enum_type: "MavBatteryType",
9649 value: tmp as u32,
9650 })?;
9651 for v in &mut __struct.serial_number {
9652 let val = buf.get_u8();
9653 *v = val;
9654 }
9655 for v in &mut __struct.device_name {
9656 let val = buf.get_u8();
9657 *v = val;
9658 }
9659 __struct.charging_maximum_voltage = buf.get_u16_le();
9660 __struct.cells_in_series = buf.get_u8();
9661 __struct.discharge_maximum_current = buf.get_u32_le();
9662 __struct.discharge_maximum_burst_current = buf.get_u32_le();
9663 for v in &mut __struct.manufacture_date {
9664 let val = buf.get_u8();
9665 *v = val;
9666 }
9667 Ok(__struct)
9668 }
9669 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9670 let mut __tmp = BytesMut::new(bytes);
9671 #[allow(clippy::absurd_extreme_comparisons)]
9672 #[allow(unused_comparisons)]
9673 if __tmp.remaining() < Self::ENCODED_LEN {
9674 panic!(
9675 "buffer is too small (need {} bytes, but got {})",
9676 Self::ENCODED_LEN,
9677 __tmp.remaining(),
9678 )
9679 }
9680 __tmp.put_i32_le(self.capacity_full_specification);
9681 __tmp.put_i32_le(self.capacity_full);
9682 __tmp.put_u16_le(self.cycle_count);
9683 __tmp.put_u16_le(self.weight);
9684 __tmp.put_u16_le(self.discharge_minimum_voltage);
9685 __tmp.put_u16_le(self.charging_minimum_voltage);
9686 __tmp.put_u16_le(self.resting_minimum_voltage);
9687 __tmp.put_u8(self.id);
9688 __tmp.put_u8(self.battery_function as u8);
9689 __tmp.put_u8(self.mavtype as u8);
9690 for val in &self.serial_number {
9691 __tmp.put_u8(*val);
9692 }
9693 for val in &self.device_name {
9694 __tmp.put_u8(*val);
9695 }
9696 __tmp.put_u16_le(self.charging_maximum_voltage);
9697 __tmp.put_u8(self.cells_in_series);
9698 __tmp.put_u32_le(self.discharge_maximum_current);
9699 __tmp.put_u32_le(self.discharge_maximum_burst_current);
9700 for val in &self.manufacture_date {
9701 __tmp.put_u8(*val);
9702 }
9703 if matches!(version, MavlinkVersion::V2) {
9704 let len = __tmp.len();
9705 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9706 } else {
9707 __tmp.len()
9708 }
9709 }
9710}
9711#[doc = "id: 291"]
9712#[doc = "ESC information for higher rate streaming. Recommended streaming rate is ~10 Hz. Information that changes more slowly is sent in ESC_INFO. It should typically only be streamed on high-bandwidth links (i.e. to a companion computer)."]
9713#[derive(Debug, Clone, PartialEq)]
9714#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9715#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9716pub struct ESC_STATUS_DATA {
9717 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number."]
9718 pub time_usec: u64,
9719 #[doc = "Reported motor RPM from each ESC (negative for reverse rotation)."]
9720 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9721 pub rpm: [i32; 4],
9722 #[doc = "Voltage measured from each ESC."]
9723 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9724 pub voltage: [f32; 4],
9725 #[doc = "Current measured from each ESC."]
9726 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9727 pub current: [f32; 4],
9728 #[doc = "Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4."]
9729 pub index: u8,
9730}
9731impl ESC_STATUS_DATA {
9732 pub const ENCODED_LEN: usize = 57usize;
9733 pub const DEFAULT: Self = Self {
9734 time_usec: 0_u64,
9735 rpm: [0_i32; 4usize],
9736 voltage: [0.0_f32; 4usize],
9737 current: [0.0_f32; 4usize],
9738 index: 0_u8,
9739 };
9740 #[cfg(feature = "arbitrary")]
9741 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9742 use arbitrary::{Arbitrary, Unstructured};
9743 let mut buf = [0u8; 1024];
9744 rng.fill_bytes(&mut buf);
9745 let mut unstructured = Unstructured::new(&buf);
9746 Self::arbitrary(&mut unstructured).unwrap_or_default()
9747 }
9748}
9749impl Default for ESC_STATUS_DATA {
9750 fn default() -> Self {
9751 Self::DEFAULT.clone()
9752 }
9753}
9754impl MessageData for ESC_STATUS_DATA {
9755 type Message = MavMessage;
9756 const ID: u32 = 291u32;
9757 const NAME: &'static str = "ESC_STATUS";
9758 const EXTRA_CRC: u8 = 10u8;
9759 const ENCODED_LEN: usize = 57usize;
9760 fn deser(
9761 _version: MavlinkVersion,
9762 __input: &[u8],
9763 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9764 let avail_len = __input.len();
9765 let mut payload_buf = [0; Self::ENCODED_LEN];
9766 let mut buf = if avail_len < Self::ENCODED_LEN {
9767 payload_buf[0..avail_len].copy_from_slice(__input);
9768 Bytes::new(&payload_buf)
9769 } else {
9770 Bytes::new(__input)
9771 };
9772 let mut __struct = Self::default();
9773 __struct.time_usec = buf.get_u64_le();
9774 for v in &mut __struct.rpm {
9775 let val = buf.get_i32_le();
9776 *v = val;
9777 }
9778 for v in &mut __struct.voltage {
9779 let val = buf.get_f32_le();
9780 *v = val;
9781 }
9782 for v in &mut __struct.current {
9783 let val = buf.get_f32_le();
9784 *v = val;
9785 }
9786 __struct.index = buf.get_u8();
9787 Ok(__struct)
9788 }
9789 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9790 let mut __tmp = BytesMut::new(bytes);
9791 #[allow(clippy::absurd_extreme_comparisons)]
9792 #[allow(unused_comparisons)]
9793 if __tmp.remaining() < Self::ENCODED_LEN {
9794 panic!(
9795 "buffer is too small (need {} bytes, but got {})",
9796 Self::ENCODED_LEN,
9797 __tmp.remaining(),
9798 )
9799 }
9800 __tmp.put_u64_le(self.time_usec);
9801 for val in &self.rpm {
9802 __tmp.put_i32_le(*val);
9803 }
9804 for val in &self.voltage {
9805 __tmp.put_f32_le(*val);
9806 }
9807 for val in &self.current {
9808 __tmp.put_f32_le(*val);
9809 }
9810 __tmp.put_u8(self.index);
9811 if matches!(version, MavlinkVersion::V2) {
9812 let len = __tmp.len();
9813 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9814 } else {
9815 __tmp.len()
9816 }
9817 }
9818}
9819#[doc = "id: 247"]
9820#[doc = "Information about a potential collision."]
9821#[derive(Debug, Clone, PartialEq)]
9822#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9823#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9824pub struct COLLISION_DATA {
9825 #[doc = "Unique identifier, domain based on src field"]
9826 pub id: u32,
9827 #[doc = "Estimated time until collision occurs"]
9828 pub time_to_minimum_delta: f32,
9829 #[doc = "Closest vertical distance between vehicle and object"]
9830 pub altitude_minimum_delta: f32,
9831 #[doc = "Closest horizontal distance between vehicle and object"]
9832 pub horizontal_minimum_delta: f32,
9833 #[doc = "Collision data source"]
9834 pub src: MavCollisionSrc,
9835 #[doc = "Action that is being taken to avoid this collision"]
9836 pub action: MavCollisionAction,
9837 #[doc = "How concerned the aircraft is about this collision"]
9838 pub threat_level: MavCollisionThreatLevel,
9839}
9840impl COLLISION_DATA {
9841 pub const ENCODED_LEN: usize = 19usize;
9842 pub const DEFAULT: Self = Self {
9843 id: 0_u32,
9844 time_to_minimum_delta: 0.0_f32,
9845 altitude_minimum_delta: 0.0_f32,
9846 horizontal_minimum_delta: 0.0_f32,
9847 src: MavCollisionSrc::DEFAULT,
9848 action: MavCollisionAction::DEFAULT,
9849 threat_level: MavCollisionThreatLevel::DEFAULT,
9850 };
9851 #[cfg(feature = "arbitrary")]
9852 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9853 use arbitrary::{Arbitrary, Unstructured};
9854 let mut buf = [0u8; 1024];
9855 rng.fill_bytes(&mut buf);
9856 let mut unstructured = Unstructured::new(&buf);
9857 Self::arbitrary(&mut unstructured).unwrap_or_default()
9858 }
9859}
9860impl Default for COLLISION_DATA {
9861 fn default() -> Self {
9862 Self::DEFAULT.clone()
9863 }
9864}
9865impl MessageData for COLLISION_DATA {
9866 type Message = MavMessage;
9867 const ID: u32 = 247u32;
9868 const NAME: &'static str = "COLLISION";
9869 const EXTRA_CRC: u8 = 81u8;
9870 const ENCODED_LEN: usize = 19usize;
9871 fn deser(
9872 _version: MavlinkVersion,
9873 __input: &[u8],
9874 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9875 let avail_len = __input.len();
9876 let mut payload_buf = [0; Self::ENCODED_LEN];
9877 let mut buf = if avail_len < Self::ENCODED_LEN {
9878 payload_buf[0..avail_len].copy_from_slice(__input);
9879 Bytes::new(&payload_buf)
9880 } else {
9881 Bytes::new(__input)
9882 };
9883 let mut __struct = Self::default();
9884 __struct.id = buf.get_u32_le();
9885 __struct.time_to_minimum_delta = buf.get_f32_le();
9886 __struct.altitude_minimum_delta = buf.get_f32_le();
9887 __struct.horizontal_minimum_delta = buf.get_f32_le();
9888 let tmp = buf.get_u8();
9889 __struct.src =
9890 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9891 enum_type: "MavCollisionSrc",
9892 value: tmp as u32,
9893 })?;
9894 let tmp = buf.get_u8();
9895 __struct.action =
9896 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9897 enum_type: "MavCollisionAction",
9898 value: tmp as u32,
9899 })?;
9900 let tmp = buf.get_u8();
9901 __struct.threat_level =
9902 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9903 enum_type: "MavCollisionThreatLevel",
9904 value: tmp as u32,
9905 })?;
9906 Ok(__struct)
9907 }
9908 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9909 let mut __tmp = BytesMut::new(bytes);
9910 #[allow(clippy::absurd_extreme_comparisons)]
9911 #[allow(unused_comparisons)]
9912 if __tmp.remaining() < Self::ENCODED_LEN {
9913 panic!(
9914 "buffer is too small (need {} bytes, but got {})",
9915 Self::ENCODED_LEN,
9916 __tmp.remaining(),
9917 )
9918 }
9919 __tmp.put_u32_le(self.id);
9920 __tmp.put_f32_le(self.time_to_minimum_delta);
9921 __tmp.put_f32_le(self.altitude_minimum_delta);
9922 __tmp.put_f32_le(self.horizontal_minimum_delta);
9923 __tmp.put_u8(self.src as u8);
9924 __tmp.put_u8(self.action as u8);
9925 __tmp.put_u8(self.threat_level as u8);
9926 if matches!(version, MavlinkVersion::V2) {
9927 let len = __tmp.len();
9928 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9929 } else {
9930 __tmp.len()
9931 }
9932 }
9933}
9934#[doc = "id: 266"]
9935#[doc = "A message containing logged data (see also MAV_CMD_LOGGING_START)."]
9936#[derive(Debug, Clone, PartialEq)]
9937#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9938#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9939pub struct LOGGING_DATA_DATA {
9940 #[doc = "sequence number (can wrap)"]
9941 pub sequence: u16,
9942 #[doc = "system ID of the target"]
9943 pub target_system: u8,
9944 #[doc = "component ID of the target"]
9945 pub target_component: u8,
9946 #[doc = "data length"]
9947 pub length: u8,
9948 #[doc = "offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists)."]
9949 pub first_message_offset: u8,
9950 #[doc = "logged data"]
9951 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9952 pub data: [u8; 249],
9953}
9954impl LOGGING_DATA_DATA {
9955 pub const ENCODED_LEN: usize = 255usize;
9956 pub const DEFAULT: Self = Self {
9957 sequence: 0_u16,
9958 target_system: 0_u8,
9959 target_component: 0_u8,
9960 length: 0_u8,
9961 first_message_offset: 0_u8,
9962 data: [0_u8; 249usize],
9963 };
9964 #[cfg(feature = "arbitrary")]
9965 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9966 use arbitrary::{Arbitrary, Unstructured};
9967 let mut buf = [0u8; 1024];
9968 rng.fill_bytes(&mut buf);
9969 let mut unstructured = Unstructured::new(&buf);
9970 Self::arbitrary(&mut unstructured).unwrap_or_default()
9971 }
9972}
9973impl Default for LOGGING_DATA_DATA {
9974 fn default() -> Self {
9975 Self::DEFAULT.clone()
9976 }
9977}
9978impl MessageData for LOGGING_DATA_DATA {
9979 type Message = MavMessage;
9980 const ID: u32 = 266u32;
9981 const NAME: &'static str = "LOGGING_DATA";
9982 const EXTRA_CRC: u8 = 193u8;
9983 const ENCODED_LEN: usize = 255usize;
9984 fn deser(
9985 _version: MavlinkVersion,
9986 __input: &[u8],
9987 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9988 let avail_len = __input.len();
9989 let mut payload_buf = [0; Self::ENCODED_LEN];
9990 let mut buf = if avail_len < Self::ENCODED_LEN {
9991 payload_buf[0..avail_len].copy_from_slice(__input);
9992 Bytes::new(&payload_buf)
9993 } else {
9994 Bytes::new(__input)
9995 };
9996 let mut __struct = Self::default();
9997 __struct.sequence = buf.get_u16_le();
9998 __struct.target_system = buf.get_u8();
9999 __struct.target_component = buf.get_u8();
10000 __struct.length = buf.get_u8();
10001 __struct.first_message_offset = buf.get_u8();
10002 for v in &mut __struct.data {
10003 let val = buf.get_u8();
10004 *v = val;
10005 }
10006 Ok(__struct)
10007 }
10008 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10009 let mut __tmp = BytesMut::new(bytes);
10010 #[allow(clippy::absurd_extreme_comparisons)]
10011 #[allow(unused_comparisons)]
10012 if __tmp.remaining() < Self::ENCODED_LEN {
10013 panic!(
10014 "buffer is too small (need {} bytes, but got {})",
10015 Self::ENCODED_LEN,
10016 __tmp.remaining(),
10017 )
10018 }
10019 __tmp.put_u16_le(self.sequence);
10020 __tmp.put_u8(self.target_system);
10021 __tmp.put_u8(self.target_component);
10022 __tmp.put_u8(self.length);
10023 __tmp.put_u8(self.first_message_offset);
10024 for val in &self.data {
10025 __tmp.put_u8(*val);
10026 }
10027 if matches!(version, MavlinkVersion::V2) {
10028 let len = __tmp.len();
10029 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10030 } else {
10031 __tmp.len()
10032 }
10033 }
10034}
10035#[doc = "id: 232"]
10036#[doc = "GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system."]
10037#[derive(Debug, Clone, PartialEq)]
10038#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10039#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10040pub struct GPS_INPUT_DATA {
10041 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
10042 pub time_usec: u64,
10043 #[doc = "GPS time (from start of GPS week)"]
10044 pub time_week_ms: u32,
10045 #[doc = "Latitude (WGS84)"]
10046 pub lat: i32,
10047 #[doc = "Longitude (WGS84)"]
10048 pub lon: i32,
10049 #[doc = "Altitude (MSL). Positive for up."]
10050 pub alt: f32,
10051 #[doc = "GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX"]
10052 pub hdop: f32,
10053 #[doc = "GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX"]
10054 pub vdop: f32,
10055 #[doc = "GPS velocity in north direction in earth-fixed NED frame"]
10056 pub vn: f32,
10057 #[doc = "GPS velocity in east direction in earth-fixed NED frame"]
10058 pub ve: f32,
10059 #[doc = "GPS velocity in down direction in earth-fixed NED frame"]
10060 pub vd: f32,
10061 #[doc = "GPS speed accuracy"]
10062 pub speed_accuracy: f32,
10063 #[doc = "GPS horizontal accuracy"]
10064 pub horiz_accuracy: f32,
10065 #[doc = "GPS vertical accuracy"]
10066 pub vert_accuracy: f32,
10067 #[doc = "Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided."]
10068 pub ignore_flags: GpsInputIgnoreFlags,
10069 #[doc = "GPS week number"]
10070 pub time_week: u16,
10071 #[doc = "ID of the GPS for multiple GPS inputs"]
10072 pub gps_id: u8,
10073 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK"]
10074 pub fix_type: u8,
10075 #[doc = "Number of satellites visible."]
10076 pub satellites_visible: u8,
10077 #[doc = "Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north"]
10078 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10079 pub yaw: u16,
10080}
10081impl GPS_INPUT_DATA {
10082 pub const ENCODED_LEN: usize = 65usize;
10083 pub const DEFAULT: Self = Self {
10084 time_usec: 0_u64,
10085 time_week_ms: 0_u32,
10086 lat: 0_i32,
10087 lon: 0_i32,
10088 alt: 0.0_f32,
10089 hdop: 0.0_f32,
10090 vdop: 0.0_f32,
10091 vn: 0.0_f32,
10092 ve: 0.0_f32,
10093 vd: 0.0_f32,
10094 speed_accuracy: 0.0_f32,
10095 horiz_accuracy: 0.0_f32,
10096 vert_accuracy: 0.0_f32,
10097 ignore_flags: GpsInputIgnoreFlags::DEFAULT,
10098 time_week: 0_u16,
10099 gps_id: 0_u8,
10100 fix_type: 0_u8,
10101 satellites_visible: 0_u8,
10102 yaw: 0_u16,
10103 };
10104 #[cfg(feature = "arbitrary")]
10105 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10106 use arbitrary::{Arbitrary, Unstructured};
10107 let mut buf = [0u8; 1024];
10108 rng.fill_bytes(&mut buf);
10109 let mut unstructured = Unstructured::new(&buf);
10110 Self::arbitrary(&mut unstructured).unwrap_or_default()
10111 }
10112}
10113impl Default for GPS_INPUT_DATA {
10114 fn default() -> Self {
10115 Self::DEFAULT.clone()
10116 }
10117}
10118impl MessageData for GPS_INPUT_DATA {
10119 type Message = MavMessage;
10120 const ID: u32 = 232u32;
10121 const NAME: &'static str = "GPS_INPUT";
10122 const EXTRA_CRC: u8 = 151u8;
10123 const ENCODED_LEN: usize = 65usize;
10124 fn deser(
10125 _version: MavlinkVersion,
10126 __input: &[u8],
10127 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10128 let avail_len = __input.len();
10129 let mut payload_buf = [0; Self::ENCODED_LEN];
10130 let mut buf = if avail_len < Self::ENCODED_LEN {
10131 payload_buf[0..avail_len].copy_from_slice(__input);
10132 Bytes::new(&payload_buf)
10133 } else {
10134 Bytes::new(__input)
10135 };
10136 let mut __struct = Self::default();
10137 __struct.time_usec = buf.get_u64_le();
10138 __struct.time_week_ms = buf.get_u32_le();
10139 __struct.lat = buf.get_i32_le();
10140 __struct.lon = buf.get_i32_le();
10141 __struct.alt = buf.get_f32_le();
10142 __struct.hdop = buf.get_f32_le();
10143 __struct.vdop = buf.get_f32_le();
10144 __struct.vn = buf.get_f32_le();
10145 __struct.ve = buf.get_f32_le();
10146 __struct.vd = buf.get_f32_le();
10147 __struct.speed_accuracy = buf.get_f32_le();
10148 __struct.horiz_accuracy = buf.get_f32_le();
10149 __struct.vert_accuracy = buf.get_f32_le();
10150 let tmp = buf.get_u16_le();
10151 __struct.ignore_flags = GpsInputIgnoreFlags::from_bits(
10152 tmp & GpsInputIgnoreFlags::all().bits(),
10153 )
10154 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
10155 flag_type: "GpsInputIgnoreFlags",
10156 value: tmp as u32,
10157 })?;
10158 __struct.time_week = buf.get_u16_le();
10159 __struct.gps_id = buf.get_u8();
10160 __struct.fix_type = buf.get_u8();
10161 __struct.satellites_visible = buf.get_u8();
10162 __struct.yaw = buf.get_u16_le();
10163 Ok(__struct)
10164 }
10165 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10166 let mut __tmp = BytesMut::new(bytes);
10167 #[allow(clippy::absurd_extreme_comparisons)]
10168 #[allow(unused_comparisons)]
10169 if __tmp.remaining() < Self::ENCODED_LEN {
10170 panic!(
10171 "buffer is too small (need {} bytes, but got {})",
10172 Self::ENCODED_LEN,
10173 __tmp.remaining(),
10174 )
10175 }
10176 __tmp.put_u64_le(self.time_usec);
10177 __tmp.put_u32_le(self.time_week_ms);
10178 __tmp.put_i32_le(self.lat);
10179 __tmp.put_i32_le(self.lon);
10180 __tmp.put_f32_le(self.alt);
10181 __tmp.put_f32_le(self.hdop);
10182 __tmp.put_f32_le(self.vdop);
10183 __tmp.put_f32_le(self.vn);
10184 __tmp.put_f32_le(self.ve);
10185 __tmp.put_f32_le(self.vd);
10186 __tmp.put_f32_le(self.speed_accuracy);
10187 __tmp.put_f32_le(self.horiz_accuracy);
10188 __tmp.put_f32_le(self.vert_accuracy);
10189 __tmp.put_u16_le(self.ignore_flags.bits());
10190 __tmp.put_u16_le(self.time_week);
10191 __tmp.put_u8(self.gps_id);
10192 __tmp.put_u8(self.fix_type);
10193 __tmp.put_u8(self.satellites_visible);
10194 __tmp.put_u16_le(self.yaw);
10195 if matches!(version, MavlinkVersion::V2) {
10196 let len = __tmp.len();
10197 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10198 } else {
10199 __tmp.len()
10200 }
10201 }
10202}
10203#[doc = "id: 242"]
10204#[doc = "Contains the home position. \tThe home position is the default position that the system will return to and land on. \tThe position must be set automatically by the system during the takeoff, and may also be explicitly set using MAV_CMD_DO_SET_HOME. \tThe global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. \tUnder normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. \tThe approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: this message can be requested by sending the MAV_CMD_REQUEST_MESSAGE with param1=242 (or the deprecated MAV_CMD_GET_HOME_POSITION command)."]
10205#[derive(Debug, Clone, PartialEq)]
10206#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10207#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10208pub struct HOME_POSITION_DATA {
10209 #[doc = "Latitude (WGS84)"]
10210 pub latitude: i32,
10211 #[doc = "Longitude (WGS84)"]
10212 pub longitude: i32,
10213 #[doc = "Altitude (MSL). Positive for up."]
10214 pub altitude: i32,
10215 #[doc = "Local X position of this position in the local coordinate frame (NED)"]
10216 pub x: f32,
10217 #[doc = "Local Y position of this position in the local coordinate frame (NED)"]
10218 pub y: f32,
10219 #[doc = "Local Z position of this position in the local coordinate frame (NED: positive \"down\")"]
10220 pub z: f32,
10221 #[doc = "Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground. All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied."]
10222 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10223 pub q: [f32; 4],
10224 #[doc = "Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
10225 pub approach_x: f32,
10226 #[doc = "Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
10227 pub approach_y: f32,
10228 #[doc = "Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
10229 pub approach_z: f32,
10230 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
10231 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10232 pub time_usec: u64,
10233}
10234impl HOME_POSITION_DATA {
10235 pub const ENCODED_LEN: usize = 60usize;
10236 pub const DEFAULT: Self = Self {
10237 latitude: 0_i32,
10238 longitude: 0_i32,
10239 altitude: 0_i32,
10240 x: 0.0_f32,
10241 y: 0.0_f32,
10242 z: 0.0_f32,
10243 q: [0.0_f32; 4usize],
10244 approach_x: 0.0_f32,
10245 approach_y: 0.0_f32,
10246 approach_z: 0.0_f32,
10247 time_usec: 0_u64,
10248 };
10249 #[cfg(feature = "arbitrary")]
10250 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10251 use arbitrary::{Arbitrary, Unstructured};
10252 let mut buf = [0u8; 1024];
10253 rng.fill_bytes(&mut buf);
10254 let mut unstructured = Unstructured::new(&buf);
10255 Self::arbitrary(&mut unstructured).unwrap_or_default()
10256 }
10257}
10258impl Default for HOME_POSITION_DATA {
10259 fn default() -> Self {
10260 Self::DEFAULT.clone()
10261 }
10262}
10263impl MessageData for HOME_POSITION_DATA {
10264 type Message = MavMessage;
10265 const ID: u32 = 242u32;
10266 const NAME: &'static str = "HOME_POSITION";
10267 const EXTRA_CRC: u8 = 104u8;
10268 const ENCODED_LEN: usize = 60usize;
10269 fn deser(
10270 _version: MavlinkVersion,
10271 __input: &[u8],
10272 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10273 let avail_len = __input.len();
10274 let mut payload_buf = [0; Self::ENCODED_LEN];
10275 let mut buf = if avail_len < Self::ENCODED_LEN {
10276 payload_buf[0..avail_len].copy_from_slice(__input);
10277 Bytes::new(&payload_buf)
10278 } else {
10279 Bytes::new(__input)
10280 };
10281 let mut __struct = Self::default();
10282 __struct.latitude = buf.get_i32_le();
10283 __struct.longitude = buf.get_i32_le();
10284 __struct.altitude = buf.get_i32_le();
10285 __struct.x = buf.get_f32_le();
10286 __struct.y = buf.get_f32_le();
10287 __struct.z = buf.get_f32_le();
10288 for v in &mut __struct.q {
10289 let val = buf.get_f32_le();
10290 *v = val;
10291 }
10292 __struct.approach_x = buf.get_f32_le();
10293 __struct.approach_y = buf.get_f32_le();
10294 __struct.approach_z = buf.get_f32_le();
10295 __struct.time_usec = buf.get_u64_le();
10296 Ok(__struct)
10297 }
10298 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10299 let mut __tmp = BytesMut::new(bytes);
10300 #[allow(clippy::absurd_extreme_comparisons)]
10301 #[allow(unused_comparisons)]
10302 if __tmp.remaining() < Self::ENCODED_LEN {
10303 panic!(
10304 "buffer is too small (need {} bytes, but got {})",
10305 Self::ENCODED_LEN,
10306 __tmp.remaining(),
10307 )
10308 }
10309 __tmp.put_i32_le(self.latitude);
10310 __tmp.put_i32_le(self.longitude);
10311 __tmp.put_i32_le(self.altitude);
10312 __tmp.put_f32_le(self.x);
10313 __tmp.put_f32_le(self.y);
10314 __tmp.put_f32_le(self.z);
10315 for val in &self.q {
10316 __tmp.put_f32_le(*val);
10317 }
10318 __tmp.put_f32_le(self.approach_x);
10319 __tmp.put_f32_le(self.approach_y);
10320 __tmp.put_f32_le(self.approach_z);
10321 __tmp.put_u64_le(self.time_usec);
10322 if matches!(version, MavlinkVersion::V2) {
10323 let len = __tmp.len();
10324 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10325 } else {
10326 __tmp.len()
10327 }
10328 }
10329}
10330#[doc = "id: 320"]
10331#[doc = "Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response."]
10332#[derive(Debug, Clone, PartialEq)]
10333#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10334#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10335pub struct PARAM_EXT_REQUEST_READ_DATA {
10336 #[doc = "Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored)"]
10337 pub param_index: i16,
10338 #[doc = "System ID"]
10339 pub target_system: u8,
10340 #[doc = "Component ID"]
10341 pub target_component: u8,
10342 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
10343 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10344 pub param_id: [u8; 16],
10345}
10346impl PARAM_EXT_REQUEST_READ_DATA {
10347 pub const ENCODED_LEN: usize = 20usize;
10348 pub const DEFAULT: Self = Self {
10349 param_index: 0_i16,
10350 target_system: 0_u8,
10351 target_component: 0_u8,
10352 param_id: [0_u8; 16usize],
10353 };
10354 #[cfg(feature = "arbitrary")]
10355 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10356 use arbitrary::{Arbitrary, Unstructured};
10357 let mut buf = [0u8; 1024];
10358 rng.fill_bytes(&mut buf);
10359 let mut unstructured = Unstructured::new(&buf);
10360 Self::arbitrary(&mut unstructured).unwrap_or_default()
10361 }
10362}
10363impl Default for PARAM_EXT_REQUEST_READ_DATA {
10364 fn default() -> Self {
10365 Self::DEFAULT.clone()
10366 }
10367}
10368impl MessageData for PARAM_EXT_REQUEST_READ_DATA {
10369 type Message = MavMessage;
10370 const ID: u32 = 320u32;
10371 const NAME: &'static str = "PARAM_EXT_REQUEST_READ";
10372 const EXTRA_CRC: u8 = 243u8;
10373 const ENCODED_LEN: usize = 20usize;
10374 fn deser(
10375 _version: MavlinkVersion,
10376 __input: &[u8],
10377 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10378 let avail_len = __input.len();
10379 let mut payload_buf = [0; Self::ENCODED_LEN];
10380 let mut buf = if avail_len < Self::ENCODED_LEN {
10381 payload_buf[0..avail_len].copy_from_slice(__input);
10382 Bytes::new(&payload_buf)
10383 } else {
10384 Bytes::new(__input)
10385 };
10386 let mut __struct = Self::default();
10387 __struct.param_index = buf.get_i16_le();
10388 __struct.target_system = buf.get_u8();
10389 __struct.target_component = buf.get_u8();
10390 for v in &mut __struct.param_id {
10391 let val = buf.get_u8();
10392 *v = val;
10393 }
10394 Ok(__struct)
10395 }
10396 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10397 let mut __tmp = BytesMut::new(bytes);
10398 #[allow(clippy::absurd_extreme_comparisons)]
10399 #[allow(unused_comparisons)]
10400 if __tmp.remaining() < Self::ENCODED_LEN {
10401 panic!(
10402 "buffer is too small (need {} bytes, but got {})",
10403 Self::ENCODED_LEN,
10404 __tmp.remaining(),
10405 )
10406 }
10407 __tmp.put_i16_le(self.param_index);
10408 __tmp.put_u8(self.target_system);
10409 __tmp.put_u8(self.target_component);
10410 for val in &self.param_id {
10411 __tmp.put_u8(*val);
10412 }
10413 if matches!(version, MavlinkVersion::V2) {
10414 let len = __tmp.len();
10415 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10416 } else {
10417 __tmp.len()
10418 }
10419 }
10420}
10421#[doc = "id: 117"]
10422#[doc = "Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0."]
10423#[derive(Debug, Clone, PartialEq)]
10424#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10425#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10426pub struct LOG_REQUEST_LIST_DATA {
10427 #[doc = "First log id (0 for first available)"]
10428 pub start: u16,
10429 #[doc = "Last log id (0xffff for last available)"]
10430 pub end: u16,
10431 #[doc = "System ID"]
10432 pub target_system: u8,
10433 #[doc = "Component ID"]
10434 pub target_component: u8,
10435}
10436impl LOG_REQUEST_LIST_DATA {
10437 pub const ENCODED_LEN: usize = 6usize;
10438 pub const DEFAULT: Self = Self {
10439 start: 0_u16,
10440 end: 0_u16,
10441 target_system: 0_u8,
10442 target_component: 0_u8,
10443 };
10444 #[cfg(feature = "arbitrary")]
10445 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10446 use arbitrary::{Arbitrary, Unstructured};
10447 let mut buf = [0u8; 1024];
10448 rng.fill_bytes(&mut buf);
10449 let mut unstructured = Unstructured::new(&buf);
10450 Self::arbitrary(&mut unstructured).unwrap_or_default()
10451 }
10452}
10453impl Default for LOG_REQUEST_LIST_DATA {
10454 fn default() -> Self {
10455 Self::DEFAULT.clone()
10456 }
10457}
10458impl MessageData for LOG_REQUEST_LIST_DATA {
10459 type Message = MavMessage;
10460 const ID: u32 = 117u32;
10461 const NAME: &'static str = "LOG_REQUEST_LIST";
10462 const EXTRA_CRC: u8 = 128u8;
10463 const ENCODED_LEN: usize = 6usize;
10464 fn deser(
10465 _version: MavlinkVersion,
10466 __input: &[u8],
10467 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10468 let avail_len = __input.len();
10469 let mut payload_buf = [0; Self::ENCODED_LEN];
10470 let mut buf = if avail_len < Self::ENCODED_LEN {
10471 payload_buf[0..avail_len].copy_from_slice(__input);
10472 Bytes::new(&payload_buf)
10473 } else {
10474 Bytes::new(__input)
10475 };
10476 let mut __struct = Self::default();
10477 __struct.start = buf.get_u16_le();
10478 __struct.end = buf.get_u16_le();
10479 __struct.target_system = buf.get_u8();
10480 __struct.target_component = buf.get_u8();
10481 Ok(__struct)
10482 }
10483 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10484 let mut __tmp = BytesMut::new(bytes);
10485 #[allow(clippy::absurd_extreme_comparisons)]
10486 #[allow(unused_comparisons)]
10487 if __tmp.remaining() < Self::ENCODED_LEN {
10488 panic!(
10489 "buffer is too small (need {} bytes, but got {})",
10490 Self::ENCODED_LEN,
10491 __tmp.remaining(),
10492 )
10493 }
10494 __tmp.put_u16_le(self.start);
10495 __tmp.put_u16_le(self.end);
10496 __tmp.put_u8(self.target_system);
10497 __tmp.put_u8(self.target_component);
10498 if matches!(version, MavlinkVersion::V2) {
10499 let len = __tmp.len();
10500 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10501 } else {
10502 __tmp.len()
10503 }
10504 }
10505}
10506#[doc = "id: 375"]
10507#[doc = "The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW."]
10508#[derive(Debug, Clone, PartialEq)]
10509#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10510#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10511pub struct ACTUATOR_OUTPUT_STATUS_DATA {
10512 #[doc = "Timestamp (since system boot)."]
10513 pub time_usec: u64,
10514 #[doc = "Active outputs"]
10515 pub active: u32,
10516 #[doc = "Servo / motor output array values. Zero values indicate unused channels."]
10517 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10518 pub actuator: [f32; 32],
10519}
10520impl ACTUATOR_OUTPUT_STATUS_DATA {
10521 pub const ENCODED_LEN: usize = 140usize;
10522 pub const DEFAULT: Self = Self {
10523 time_usec: 0_u64,
10524 active: 0_u32,
10525 actuator: [0.0_f32; 32usize],
10526 };
10527 #[cfg(feature = "arbitrary")]
10528 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10529 use arbitrary::{Arbitrary, Unstructured};
10530 let mut buf = [0u8; 1024];
10531 rng.fill_bytes(&mut buf);
10532 let mut unstructured = Unstructured::new(&buf);
10533 Self::arbitrary(&mut unstructured).unwrap_or_default()
10534 }
10535}
10536impl Default for ACTUATOR_OUTPUT_STATUS_DATA {
10537 fn default() -> Self {
10538 Self::DEFAULT.clone()
10539 }
10540}
10541impl MessageData for ACTUATOR_OUTPUT_STATUS_DATA {
10542 type Message = MavMessage;
10543 const ID: u32 = 375u32;
10544 const NAME: &'static str = "ACTUATOR_OUTPUT_STATUS";
10545 const EXTRA_CRC: u8 = 251u8;
10546 const ENCODED_LEN: usize = 140usize;
10547 fn deser(
10548 _version: MavlinkVersion,
10549 __input: &[u8],
10550 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10551 let avail_len = __input.len();
10552 let mut payload_buf = [0; Self::ENCODED_LEN];
10553 let mut buf = if avail_len < Self::ENCODED_LEN {
10554 payload_buf[0..avail_len].copy_from_slice(__input);
10555 Bytes::new(&payload_buf)
10556 } else {
10557 Bytes::new(__input)
10558 };
10559 let mut __struct = Self::default();
10560 __struct.time_usec = buf.get_u64_le();
10561 __struct.active = buf.get_u32_le();
10562 for v in &mut __struct.actuator {
10563 let val = buf.get_f32_le();
10564 *v = val;
10565 }
10566 Ok(__struct)
10567 }
10568 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10569 let mut __tmp = BytesMut::new(bytes);
10570 #[allow(clippy::absurd_extreme_comparisons)]
10571 #[allow(unused_comparisons)]
10572 if __tmp.remaining() < Self::ENCODED_LEN {
10573 panic!(
10574 "buffer is too small (need {} bytes, but got {})",
10575 Self::ENCODED_LEN,
10576 __tmp.remaining(),
10577 )
10578 }
10579 __tmp.put_u64_le(self.time_usec);
10580 __tmp.put_u32_le(self.active);
10581 for val in &self.actuator {
10582 __tmp.put_f32_le(*val);
10583 }
10584 if matches!(version, MavlinkVersion::V2) {
10585 let len = __tmp.len();
10586 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10587 } else {
10588 __tmp.len()
10589 }
10590 }
10591}
10592#[doc = "id: 330"]
10593#[doc = "Obstacle distances in front of the sensor, starting from the left in increment degrees to the right."]
10594#[derive(Debug, Clone, PartialEq)]
10595#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10596#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10597pub struct OBSTACLE_DISTANCE_DATA {
10598 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
10599 pub time_usec: u64,
10600 #[doc = "Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm."]
10601 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10602 pub distances: [u16; 72],
10603 #[doc = "Minimum distance the sensor can measure."]
10604 pub min_distance: u16,
10605 #[doc = "Maximum distance the sensor can measure."]
10606 pub max_distance: u16,
10607 #[doc = "Class id of the distance sensor type."]
10608 pub sensor_type: MavDistanceSensor,
10609 #[doc = "Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero."]
10610 pub increment: u8,
10611 #[doc = "Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise."]
10612 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10613 pub increment_f: f32,
10614 #[doc = "Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise."]
10615 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10616 pub angle_offset: f32,
10617 #[doc = "Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned."]
10618 #[cfg_attr(feature = "serde", serde(default))]
10619 pub frame: MavFrame,
10620}
10621impl OBSTACLE_DISTANCE_DATA {
10622 pub const ENCODED_LEN: usize = 167usize;
10623 pub const DEFAULT: Self = Self {
10624 time_usec: 0_u64,
10625 distances: [0_u16; 72usize],
10626 min_distance: 0_u16,
10627 max_distance: 0_u16,
10628 sensor_type: MavDistanceSensor::DEFAULT,
10629 increment: 0_u8,
10630 increment_f: 0.0_f32,
10631 angle_offset: 0.0_f32,
10632 frame: MavFrame::DEFAULT,
10633 };
10634 #[cfg(feature = "arbitrary")]
10635 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10636 use arbitrary::{Arbitrary, Unstructured};
10637 let mut buf = [0u8; 1024];
10638 rng.fill_bytes(&mut buf);
10639 let mut unstructured = Unstructured::new(&buf);
10640 Self::arbitrary(&mut unstructured).unwrap_or_default()
10641 }
10642}
10643impl Default for OBSTACLE_DISTANCE_DATA {
10644 fn default() -> Self {
10645 Self::DEFAULT.clone()
10646 }
10647}
10648impl MessageData for OBSTACLE_DISTANCE_DATA {
10649 type Message = MavMessage;
10650 const ID: u32 = 330u32;
10651 const NAME: &'static str = "OBSTACLE_DISTANCE";
10652 const EXTRA_CRC: u8 = 23u8;
10653 const ENCODED_LEN: usize = 167usize;
10654 fn deser(
10655 _version: MavlinkVersion,
10656 __input: &[u8],
10657 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10658 let avail_len = __input.len();
10659 let mut payload_buf = [0; Self::ENCODED_LEN];
10660 let mut buf = if avail_len < Self::ENCODED_LEN {
10661 payload_buf[0..avail_len].copy_from_slice(__input);
10662 Bytes::new(&payload_buf)
10663 } else {
10664 Bytes::new(__input)
10665 };
10666 let mut __struct = Self::default();
10667 __struct.time_usec = buf.get_u64_le();
10668 for v in &mut __struct.distances {
10669 let val = buf.get_u16_le();
10670 *v = val;
10671 }
10672 __struct.min_distance = buf.get_u16_le();
10673 __struct.max_distance = buf.get_u16_le();
10674 let tmp = buf.get_u8();
10675 __struct.sensor_type =
10676 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10677 enum_type: "MavDistanceSensor",
10678 value: tmp as u32,
10679 })?;
10680 __struct.increment = buf.get_u8();
10681 __struct.increment_f = buf.get_f32_le();
10682 __struct.angle_offset = buf.get_f32_le();
10683 let tmp = buf.get_u8();
10684 __struct.frame =
10685 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10686 enum_type: "MavFrame",
10687 value: tmp as u32,
10688 })?;
10689 Ok(__struct)
10690 }
10691 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10692 let mut __tmp = BytesMut::new(bytes);
10693 #[allow(clippy::absurd_extreme_comparisons)]
10694 #[allow(unused_comparisons)]
10695 if __tmp.remaining() < Self::ENCODED_LEN {
10696 panic!(
10697 "buffer is too small (need {} bytes, but got {})",
10698 Self::ENCODED_LEN,
10699 __tmp.remaining(),
10700 )
10701 }
10702 __tmp.put_u64_le(self.time_usec);
10703 for val in &self.distances {
10704 __tmp.put_u16_le(*val);
10705 }
10706 __tmp.put_u16_le(self.min_distance);
10707 __tmp.put_u16_le(self.max_distance);
10708 __tmp.put_u8(self.sensor_type as u8);
10709 __tmp.put_u8(self.increment);
10710 __tmp.put_f32_le(self.increment_f);
10711 __tmp.put_f32_le(self.angle_offset);
10712 __tmp.put_u8(self.frame as u8);
10713 if matches!(version, MavlinkVersion::V2) {
10714 let len = __tmp.len();
10715 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10716 } else {
10717 __tmp.len()
10718 }
10719 }
10720}
10721#[doc = "id: 231"]
10722#[doc = "Wind estimate from vehicle. Note that despite the name, this message does not actually contain any covariances but instead variability and accuracy fields in terms of standard deviation (1-STD)."]
10723#[derive(Debug, Clone, PartialEq)]
10724#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10725#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10726pub struct WIND_COV_DATA {
10727 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
10728 pub time_usec: u64,
10729 #[doc = "Wind in North (NED) direction (NAN if unknown)"]
10730 pub wind_x: f32,
10731 #[doc = "Wind in East (NED) direction (NAN if unknown)"]
10732 pub wind_y: f32,
10733 #[doc = "Wind in down (NED) direction (NAN if unknown)"]
10734 pub wind_z: f32,
10735 #[doc = "Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)"]
10736 pub var_horiz: f32,
10737 #[doc = "Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)"]
10738 pub var_vert: f32,
10739 #[doc = "Altitude (MSL) that this measurement was taken at (NAN if unknown)"]
10740 pub wind_alt: f32,
10741 #[doc = "Horizontal speed 1-STD accuracy (0 if unknown)"]
10742 pub horiz_accuracy: f32,
10743 #[doc = "Vertical speed 1-STD accuracy (0 if unknown)"]
10744 pub vert_accuracy: f32,
10745}
10746impl WIND_COV_DATA {
10747 pub const ENCODED_LEN: usize = 40usize;
10748 pub const DEFAULT: Self = Self {
10749 time_usec: 0_u64,
10750 wind_x: 0.0_f32,
10751 wind_y: 0.0_f32,
10752 wind_z: 0.0_f32,
10753 var_horiz: 0.0_f32,
10754 var_vert: 0.0_f32,
10755 wind_alt: 0.0_f32,
10756 horiz_accuracy: 0.0_f32,
10757 vert_accuracy: 0.0_f32,
10758 };
10759 #[cfg(feature = "arbitrary")]
10760 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10761 use arbitrary::{Arbitrary, Unstructured};
10762 let mut buf = [0u8; 1024];
10763 rng.fill_bytes(&mut buf);
10764 let mut unstructured = Unstructured::new(&buf);
10765 Self::arbitrary(&mut unstructured).unwrap_or_default()
10766 }
10767}
10768impl Default for WIND_COV_DATA {
10769 fn default() -> Self {
10770 Self::DEFAULT.clone()
10771 }
10772}
10773impl MessageData for WIND_COV_DATA {
10774 type Message = MavMessage;
10775 const ID: u32 = 231u32;
10776 const NAME: &'static str = "WIND_COV";
10777 const EXTRA_CRC: u8 = 105u8;
10778 const ENCODED_LEN: usize = 40usize;
10779 fn deser(
10780 _version: MavlinkVersion,
10781 __input: &[u8],
10782 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10783 let avail_len = __input.len();
10784 let mut payload_buf = [0; Self::ENCODED_LEN];
10785 let mut buf = if avail_len < Self::ENCODED_LEN {
10786 payload_buf[0..avail_len].copy_from_slice(__input);
10787 Bytes::new(&payload_buf)
10788 } else {
10789 Bytes::new(__input)
10790 };
10791 let mut __struct = Self::default();
10792 __struct.time_usec = buf.get_u64_le();
10793 __struct.wind_x = buf.get_f32_le();
10794 __struct.wind_y = buf.get_f32_le();
10795 __struct.wind_z = buf.get_f32_le();
10796 __struct.var_horiz = buf.get_f32_le();
10797 __struct.var_vert = buf.get_f32_le();
10798 __struct.wind_alt = buf.get_f32_le();
10799 __struct.horiz_accuracy = buf.get_f32_le();
10800 __struct.vert_accuracy = buf.get_f32_le();
10801 Ok(__struct)
10802 }
10803 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10804 let mut __tmp = BytesMut::new(bytes);
10805 #[allow(clippy::absurd_extreme_comparisons)]
10806 #[allow(unused_comparisons)]
10807 if __tmp.remaining() < Self::ENCODED_LEN {
10808 panic!(
10809 "buffer is too small (need {} bytes, but got {})",
10810 Self::ENCODED_LEN,
10811 __tmp.remaining(),
10812 )
10813 }
10814 __tmp.put_u64_le(self.time_usec);
10815 __tmp.put_f32_le(self.wind_x);
10816 __tmp.put_f32_le(self.wind_y);
10817 __tmp.put_f32_le(self.wind_z);
10818 __tmp.put_f32_le(self.var_horiz);
10819 __tmp.put_f32_le(self.var_vert);
10820 __tmp.put_f32_le(self.wind_alt);
10821 __tmp.put_f32_le(self.horiz_accuracy);
10822 __tmp.put_f32_le(self.vert_accuracy);
10823 if matches!(version, MavlinkVersion::V2) {
10824 let len = __tmp.len();
10825 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10826 } else {
10827 __tmp.len()
10828 }
10829 }
10830}
10831#[doc = "id: 10002"]
10832#[doc = "Dynamic data used to generate ADS-B out transponder data (send at 5Hz)."]
10833#[derive(Debug, Clone, PartialEq)]
10834#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10835#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10836pub struct UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
10837 #[doc = "UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX"]
10838 pub utcTime: u32,
10839 #[doc = "Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX"]
10840 pub gpsLat: i32,
10841 #[doc = "Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX"]
10842 pub gpsLon: i32,
10843 #[doc = "Altitude (WGS84). UP +ve. If unknown set to INT32_MAX"]
10844 pub gpsAlt: i32,
10845 #[doc = "Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX"]
10846 pub baroAltMSL: i32,
10847 #[doc = "Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX"]
10848 pub accuracyHor: u32,
10849 #[doc = "Vertical accuracy in cm. If unknown set to UINT16_MAX"]
10850 pub accuracyVert: u16,
10851 #[doc = "Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX"]
10852 pub accuracyVel: u16,
10853 #[doc = "GPS vertical speed in cm/s. If unknown set to INT16_MAX"]
10854 pub velVert: i16,
10855 #[doc = "North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX"]
10856 pub velNS: i16,
10857 #[doc = "East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX"]
10858 pub VelEW: i16,
10859 #[doc = "ADS-B transponder dynamic input state flags"]
10860 pub state: UavionixAdsbOutDynamicState,
10861 #[doc = "Mode A code (typically 1200 [0x04B0] for VFR)"]
10862 pub squawk: u16,
10863 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK"]
10864 pub gpsFix: UavionixAdsbOutDynamicGpsFix,
10865 #[doc = "Number of satellites visible. If unknown set to UINT8_MAX"]
10866 pub numSats: u8,
10867 #[doc = "Emergency status"]
10868 pub emergencyStatus: UavionixAdsbEmergencyStatus,
10869}
10870impl UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
10871 pub const ENCODED_LEN: usize = 41usize;
10872 pub const DEFAULT: Self = Self {
10873 utcTime: 0_u32,
10874 gpsLat: 0_i32,
10875 gpsLon: 0_i32,
10876 gpsAlt: 0_i32,
10877 baroAltMSL: 0_i32,
10878 accuracyHor: 0_u32,
10879 accuracyVert: 0_u16,
10880 accuracyVel: 0_u16,
10881 velVert: 0_i16,
10882 velNS: 0_i16,
10883 VelEW: 0_i16,
10884 state: UavionixAdsbOutDynamicState::DEFAULT,
10885 squawk: 0_u16,
10886 gpsFix: UavionixAdsbOutDynamicGpsFix::DEFAULT,
10887 numSats: 0_u8,
10888 emergencyStatus: UavionixAdsbEmergencyStatus::DEFAULT,
10889 };
10890 #[cfg(feature = "arbitrary")]
10891 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10892 use arbitrary::{Arbitrary, Unstructured};
10893 let mut buf = [0u8; 1024];
10894 rng.fill_bytes(&mut buf);
10895 let mut unstructured = Unstructured::new(&buf);
10896 Self::arbitrary(&mut unstructured).unwrap_or_default()
10897 }
10898}
10899impl Default for UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
10900 fn default() -> Self {
10901 Self::DEFAULT.clone()
10902 }
10903}
10904impl MessageData for UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
10905 type Message = MavMessage;
10906 const ID: u32 = 10002u32;
10907 const NAME: &'static str = "UAVIONIX_ADSB_OUT_DYNAMIC";
10908 const EXTRA_CRC: u8 = 186u8;
10909 const ENCODED_LEN: usize = 41usize;
10910 fn deser(
10911 _version: MavlinkVersion,
10912 __input: &[u8],
10913 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10914 let avail_len = __input.len();
10915 let mut payload_buf = [0; Self::ENCODED_LEN];
10916 let mut buf = if avail_len < Self::ENCODED_LEN {
10917 payload_buf[0..avail_len].copy_from_slice(__input);
10918 Bytes::new(&payload_buf)
10919 } else {
10920 Bytes::new(__input)
10921 };
10922 let mut __struct = Self::default();
10923 __struct.utcTime = buf.get_u32_le();
10924 __struct.gpsLat = buf.get_i32_le();
10925 __struct.gpsLon = buf.get_i32_le();
10926 __struct.gpsAlt = buf.get_i32_le();
10927 __struct.baroAltMSL = buf.get_i32_le();
10928 __struct.accuracyHor = buf.get_u32_le();
10929 __struct.accuracyVert = buf.get_u16_le();
10930 __struct.accuracyVel = buf.get_u16_le();
10931 __struct.velVert = buf.get_i16_le();
10932 __struct.velNS = buf.get_i16_le();
10933 __struct.VelEW = buf.get_i16_le();
10934 let tmp = buf.get_u16_le();
10935 __struct.state =
10936 UavionixAdsbOutDynamicState::from_bits(tmp & UavionixAdsbOutDynamicState::all().bits())
10937 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
10938 flag_type: "UavionixAdsbOutDynamicState",
10939 value: tmp as u32,
10940 })?;
10941 __struct.squawk = buf.get_u16_le();
10942 let tmp = buf.get_u8();
10943 __struct.gpsFix =
10944 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10945 enum_type: "UavionixAdsbOutDynamicGpsFix",
10946 value: tmp as u32,
10947 })?;
10948 __struct.numSats = buf.get_u8();
10949 let tmp = buf.get_u8();
10950 __struct.emergencyStatus =
10951 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10952 enum_type: "UavionixAdsbEmergencyStatus",
10953 value: tmp as u32,
10954 })?;
10955 Ok(__struct)
10956 }
10957 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10958 let mut __tmp = BytesMut::new(bytes);
10959 #[allow(clippy::absurd_extreme_comparisons)]
10960 #[allow(unused_comparisons)]
10961 if __tmp.remaining() < Self::ENCODED_LEN {
10962 panic!(
10963 "buffer is too small (need {} bytes, but got {})",
10964 Self::ENCODED_LEN,
10965 __tmp.remaining(),
10966 )
10967 }
10968 __tmp.put_u32_le(self.utcTime);
10969 __tmp.put_i32_le(self.gpsLat);
10970 __tmp.put_i32_le(self.gpsLon);
10971 __tmp.put_i32_le(self.gpsAlt);
10972 __tmp.put_i32_le(self.baroAltMSL);
10973 __tmp.put_u32_le(self.accuracyHor);
10974 __tmp.put_u16_le(self.accuracyVert);
10975 __tmp.put_u16_le(self.accuracyVel);
10976 __tmp.put_i16_le(self.velVert);
10977 __tmp.put_i16_le(self.velNS);
10978 __tmp.put_i16_le(self.VelEW);
10979 __tmp.put_u16_le(self.state.bits());
10980 __tmp.put_u16_le(self.squawk);
10981 __tmp.put_u8(self.gpsFix as u8);
10982 __tmp.put_u8(self.numSats);
10983 __tmp.put_u8(self.emergencyStatus as u8);
10984 if matches!(version, MavlinkVersion::V2) {
10985 let len = __tmp.len();
10986 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10987 } else {
10988 __tmp.len()
10989 }
10990 }
10991}
10992#[doc = "id: 10008"]
10993#[doc = "Status message with information from UCP Heartbeat and Status messages."]
10994#[derive(Debug, Clone, PartialEq)]
10995#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10996#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10997pub struct UAVIONIX_ADSB_OUT_STATUS_DATA {
10998 #[doc = "Mode A code (typically 1200 [0x04B0] for VFR)"]
10999 pub squawk: u16,
11000 #[doc = "ADS-B transponder status state flags"]
11001 pub state: UavionixAdsbOutStatusState,
11002 #[doc = "Integrity and Accuracy of traffic reported as a 4-bit value for each field (NACp 7:4, NIC 3:0) and encoded by Containment Radius (HPL) and Estimated Position Uncertainty (HFOM), respectively"]
11003 pub NIC_NACp: UavionixAdsbOutStatusNicNacp,
11004 #[doc = "Board temperature in C"]
11005 pub boardTemp: u8,
11006 #[doc = "ADS-B transponder fault flags"]
11007 pub fault: UavionixAdsbOutStatusFault,
11008 #[doc = "Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable."]
11009 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11010 pub flight_id: [u8; 8],
11011}
11012impl UAVIONIX_ADSB_OUT_STATUS_DATA {
11013 pub const ENCODED_LEN: usize = 14usize;
11014 pub const DEFAULT: Self = Self {
11015 squawk: 0_u16,
11016 state: UavionixAdsbOutStatusState::DEFAULT,
11017 NIC_NACp: UavionixAdsbOutStatusNicNacp::DEFAULT,
11018 boardTemp: 0_u8,
11019 fault: UavionixAdsbOutStatusFault::DEFAULT,
11020 flight_id: [0_u8; 8usize],
11021 };
11022 #[cfg(feature = "arbitrary")]
11023 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11024 use arbitrary::{Arbitrary, Unstructured};
11025 let mut buf = [0u8; 1024];
11026 rng.fill_bytes(&mut buf);
11027 let mut unstructured = Unstructured::new(&buf);
11028 Self::arbitrary(&mut unstructured).unwrap_or_default()
11029 }
11030}
11031impl Default for UAVIONIX_ADSB_OUT_STATUS_DATA {
11032 fn default() -> Self {
11033 Self::DEFAULT.clone()
11034 }
11035}
11036impl MessageData for UAVIONIX_ADSB_OUT_STATUS_DATA {
11037 type Message = MavMessage;
11038 const ID: u32 = 10008u32;
11039 const NAME: &'static str = "UAVIONIX_ADSB_OUT_STATUS";
11040 const EXTRA_CRC: u8 = 240u8;
11041 const ENCODED_LEN: usize = 14usize;
11042 fn deser(
11043 _version: MavlinkVersion,
11044 __input: &[u8],
11045 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11046 let avail_len = __input.len();
11047 let mut payload_buf = [0; Self::ENCODED_LEN];
11048 let mut buf = if avail_len < Self::ENCODED_LEN {
11049 payload_buf[0..avail_len].copy_from_slice(__input);
11050 Bytes::new(&payload_buf)
11051 } else {
11052 Bytes::new(__input)
11053 };
11054 let mut __struct = Self::default();
11055 __struct.squawk = buf.get_u16_le();
11056 let tmp = buf.get_u8();
11057 __struct.state =
11058 UavionixAdsbOutStatusState::from_bits(tmp & UavionixAdsbOutStatusState::all().bits())
11059 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
11060 flag_type: "UavionixAdsbOutStatusState",
11061 value: tmp as u32,
11062 })?;
11063 let tmp = buf.get_u8();
11064 __struct.NIC_NACp =
11065 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11066 enum_type: "UavionixAdsbOutStatusNicNacp",
11067 value: tmp as u32,
11068 })?;
11069 __struct.boardTemp = buf.get_u8();
11070 let tmp = buf.get_u8();
11071 __struct.fault =
11072 UavionixAdsbOutStatusFault::from_bits(tmp & UavionixAdsbOutStatusFault::all().bits())
11073 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
11074 flag_type: "UavionixAdsbOutStatusFault",
11075 value: tmp as u32,
11076 })?;
11077 for v in &mut __struct.flight_id {
11078 let val = buf.get_u8();
11079 *v = val;
11080 }
11081 Ok(__struct)
11082 }
11083 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11084 let mut __tmp = BytesMut::new(bytes);
11085 #[allow(clippy::absurd_extreme_comparisons)]
11086 #[allow(unused_comparisons)]
11087 if __tmp.remaining() < Self::ENCODED_LEN {
11088 panic!(
11089 "buffer is too small (need {} bytes, but got {})",
11090 Self::ENCODED_LEN,
11091 __tmp.remaining(),
11092 )
11093 }
11094 __tmp.put_u16_le(self.squawk);
11095 __tmp.put_u8(self.state.bits());
11096 __tmp.put_u8(self.NIC_NACp as u8);
11097 __tmp.put_u8(self.boardTemp);
11098 __tmp.put_u8(self.fault.bits());
11099 for val in &self.flight_id {
11100 __tmp.put_u8(*val);
11101 }
11102 if matches!(version, MavlinkVersion::V2) {
11103 let len = __tmp.len();
11104 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11105 } else {
11106 __tmp.len()
11107 }
11108 }
11109}
11110#[doc = "id: 235"]
11111#[doc = "Message appropriate for high latency connections like Iridium (version 2)."]
11112#[derive(Debug, Clone, PartialEq)]
11113#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11114#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11115pub struct HIGH_LATENCY2_DATA {
11116 #[doc = "Timestamp (milliseconds since boot or Unix epoch)"]
11117 pub timestamp: u32,
11118 #[doc = "Latitude"]
11119 pub latitude: i32,
11120 #[doc = "Longitude"]
11121 pub longitude: i32,
11122 #[doc = "A bitfield for use for autopilot-specific flags (2 byte version)."]
11123 pub custom_mode: u16,
11124 #[doc = "Altitude above mean sea level"]
11125 pub altitude: i16,
11126 #[doc = "Altitude setpoint"]
11127 pub target_altitude: i16,
11128 #[doc = "Distance to target waypoint or position"]
11129 pub target_distance: u16,
11130 #[doc = "Current waypoint number"]
11131 pub wp_num: u16,
11132 #[doc = "Bitmap of failure flags."]
11133 pub failure_flags: HlFailureFlag,
11134 #[doc = "Type of the MAV (quadrotor, helicopter, etc.)"]
11135 pub mavtype: MavType,
11136 #[doc = "Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers."]
11137 pub autopilot: MavAutopilot,
11138 #[doc = "Heading"]
11139 pub heading: u8,
11140 #[doc = "Heading setpoint"]
11141 pub target_heading: u8,
11142 #[doc = "Throttle"]
11143 pub throttle: u8,
11144 #[doc = "Airspeed"]
11145 pub airspeed: u8,
11146 #[doc = "Airspeed setpoint"]
11147 pub airspeed_sp: u8,
11148 #[doc = "Groundspeed"]
11149 pub groundspeed: u8,
11150 #[doc = "Windspeed"]
11151 pub windspeed: u8,
11152 #[doc = "Wind heading"]
11153 pub wind_heading: u8,
11154 #[doc = "Maximum error horizontal position since last message"]
11155 pub eph: u8,
11156 #[doc = "Maximum error vertical position since last message"]
11157 pub epv: u8,
11158 #[doc = "Air temperature"]
11159 pub temperature_air: i8,
11160 #[doc = "Maximum climb rate magnitude since last message"]
11161 pub climb_rate: i8,
11162 #[doc = "Battery level (-1 if field not provided)."]
11163 pub battery: i8,
11164 #[doc = "Field for custom payload."]
11165 pub custom0: i8,
11166 #[doc = "Field for custom payload."]
11167 pub custom1: i8,
11168 #[doc = "Field for custom payload."]
11169 pub custom2: i8,
11170}
11171impl HIGH_LATENCY2_DATA {
11172 pub const ENCODED_LEN: usize = 42usize;
11173 pub const DEFAULT: Self = Self {
11174 timestamp: 0_u32,
11175 latitude: 0_i32,
11176 longitude: 0_i32,
11177 custom_mode: 0_u16,
11178 altitude: 0_i16,
11179 target_altitude: 0_i16,
11180 target_distance: 0_u16,
11181 wp_num: 0_u16,
11182 failure_flags: HlFailureFlag::DEFAULT,
11183 mavtype: MavType::DEFAULT,
11184 autopilot: MavAutopilot::DEFAULT,
11185 heading: 0_u8,
11186 target_heading: 0_u8,
11187 throttle: 0_u8,
11188 airspeed: 0_u8,
11189 airspeed_sp: 0_u8,
11190 groundspeed: 0_u8,
11191 windspeed: 0_u8,
11192 wind_heading: 0_u8,
11193 eph: 0_u8,
11194 epv: 0_u8,
11195 temperature_air: 0_i8,
11196 climb_rate: 0_i8,
11197 battery: 0_i8,
11198 custom0: 0_i8,
11199 custom1: 0_i8,
11200 custom2: 0_i8,
11201 };
11202 #[cfg(feature = "arbitrary")]
11203 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11204 use arbitrary::{Arbitrary, Unstructured};
11205 let mut buf = [0u8; 1024];
11206 rng.fill_bytes(&mut buf);
11207 let mut unstructured = Unstructured::new(&buf);
11208 Self::arbitrary(&mut unstructured).unwrap_or_default()
11209 }
11210}
11211impl Default for HIGH_LATENCY2_DATA {
11212 fn default() -> Self {
11213 Self::DEFAULT.clone()
11214 }
11215}
11216impl MessageData for HIGH_LATENCY2_DATA {
11217 type Message = MavMessage;
11218 const ID: u32 = 235u32;
11219 const NAME: &'static str = "HIGH_LATENCY2";
11220 const EXTRA_CRC: u8 = 179u8;
11221 const ENCODED_LEN: usize = 42usize;
11222 fn deser(
11223 _version: MavlinkVersion,
11224 __input: &[u8],
11225 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11226 let avail_len = __input.len();
11227 let mut payload_buf = [0; Self::ENCODED_LEN];
11228 let mut buf = if avail_len < Self::ENCODED_LEN {
11229 payload_buf[0..avail_len].copy_from_slice(__input);
11230 Bytes::new(&payload_buf)
11231 } else {
11232 Bytes::new(__input)
11233 };
11234 let mut __struct = Self::default();
11235 __struct.timestamp = buf.get_u32_le();
11236 __struct.latitude = buf.get_i32_le();
11237 __struct.longitude = buf.get_i32_le();
11238 __struct.custom_mode = buf.get_u16_le();
11239 __struct.altitude = buf.get_i16_le();
11240 __struct.target_altitude = buf.get_i16_le();
11241 __struct.target_distance = buf.get_u16_le();
11242 __struct.wp_num = buf.get_u16_le();
11243 let tmp = buf.get_u16_le();
11244 __struct.failure_flags = HlFailureFlag::from_bits(tmp & HlFailureFlag::all().bits())
11245 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
11246 flag_type: "HlFailureFlag",
11247 value: tmp as u32,
11248 })?;
11249 let tmp = buf.get_u8();
11250 __struct.mavtype =
11251 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11252 enum_type: "MavType",
11253 value: tmp as u32,
11254 })?;
11255 let tmp = buf.get_u8();
11256 __struct.autopilot =
11257 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11258 enum_type: "MavAutopilot",
11259 value: tmp as u32,
11260 })?;
11261 __struct.heading = buf.get_u8();
11262 __struct.target_heading = buf.get_u8();
11263 __struct.throttle = buf.get_u8();
11264 __struct.airspeed = buf.get_u8();
11265 __struct.airspeed_sp = buf.get_u8();
11266 __struct.groundspeed = buf.get_u8();
11267 __struct.windspeed = buf.get_u8();
11268 __struct.wind_heading = buf.get_u8();
11269 __struct.eph = buf.get_u8();
11270 __struct.epv = buf.get_u8();
11271 __struct.temperature_air = buf.get_i8();
11272 __struct.climb_rate = buf.get_i8();
11273 __struct.battery = buf.get_i8();
11274 __struct.custom0 = buf.get_i8();
11275 __struct.custom1 = buf.get_i8();
11276 __struct.custom2 = buf.get_i8();
11277 Ok(__struct)
11278 }
11279 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11280 let mut __tmp = BytesMut::new(bytes);
11281 #[allow(clippy::absurd_extreme_comparisons)]
11282 #[allow(unused_comparisons)]
11283 if __tmp.remaining() < Self::ENCODED_LEN {
11284 panic!(
11285 "buffer is too small (need {} bytes, but got {})",
11286 Self::ENCODED_LEN,
11287 __tmp.remaining(),
11288 )
11289 }
11290 __tmp.put_u32_le(self.timestamp);
11291 __tmp.put_i32_le(self.latitude);
11292 __tmp.put_i32_le(self.longitude);
11293 __tmp.put_u16_le(self.custom_mode);
11294 __tmp.put_i16_le(self.altitude);
11295 __tmp.put_i16_le(self.target_altitude);
11296 __tmp.put_u16_le(self.target_distance);
11297 __tmp.put_u16_le(self.wp_num);
11298 __tmp.put_u16_le(self.failure_flags.bits());
11299 __tmp.put_u8(self.mavtype as u8);
11300 __tmp.put_u8(self.autopilot as u8);
11301 __tmp.put_u8(self.heading);
11302 __tmp.put_u8(self.target_heading);
11303 __tmp.put_u8(self.throttle);
11304 __tmp.put_u8(self.airspeed);
11305 __tmp.put_u8(self.airspeed_sp);
11306 __tmp.put_u8(self.groundspeed);
11307 __tmp.put_u8(self.windspeed);
11308 __tmp.put_u8(self.wind_heading);
11309 __tmp.put_u8(self.eph);
11310 __tmp.put_u8(self.epv);
11311 __tmp.put_i8(self.temperature_air);
11312 __tmp.put_i8(self.climb_rate);
11313 __tmp.put_i8(self.battery);
11314 __tmp.put_i8(self.custom0);
11315 __tmp.put_i8(self.custom1);
11316 __tmp.put_i8(self.custom2);
11317 if matches!(version, MavlinkVersion::V2) {
11318 let len = __tmp.len();
11319 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11320 } else {
11321 __tmp.len()
11322 }
11323 }
11324}
11325#[doc = "id: 284"]
11326#[doc = "Low level message to control a gimbal device's attitude. \t This message is to be sent from the gimbal manager to the gimbal device component. \t The quaternion and angular velocities can be set to NaN according to use case. \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. \t These rules are to ensure backwards compatibility. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME."]
11327#[derive(Debug, Clone, PartialEq)]
11328#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11329#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11330pub struct GIMBAL_DEVICE_SET_ATTITUDE_DATA {
11331 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored."]
11332 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11333 pub q: [f32; 4],
11334 #[doc = "X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored."]
11335 pub angular_velocity_x: f32,
11336 #[doc = "Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored."]
11337 pub angular_velocity_y: f32,
11338 #[doc = "Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored."]
11339 pub angular_velocity_z: f32,
11340 #[doc = "Low level gimbal flags."]
11341 pub flags: GimbalDeviceFlags,
11342 #[doc = "System ID"]
11343 pub target_system: u8,
11344 #[doc = "Component ID"]
11345 pub target_component: u8,
11346}
11347impl GIMBAL_DEVICE_SET_ATTITUDE_DATA {
11348 pub const ENCODED_LEN: usize = 32usize;
11349 pub const DEFAULT: Self = Self {
11350 q: [0.0_f32; 4usize],
11351 angular_velocity_x: 0.0_f32,
11352 angular_velocity_y: 0.0_f32,
11353 angular_velocity_z: 0.0_f32,
11354 flags: GimbalDeviceFlags::DEFAULT,
11355 target_system: 0_u8,
11356 target_component: 0_u8,
11357 };
11358 #[cfg(feature = "arbitrary")]
11359 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11360 use arbitrary::{Arbitrary, Unstructured};
11361 let mut buf = [0u8; 1024];
11362 rng.fill_bytes(&mut buf);
11363 let mut unstructured = Unstructured::new(&buf);
11364 Self::arbitrary(&mut unstructured).unwrap_or_default()
11365 }
11366}
11367impl Default for GIMBAL_DEVICE_SET_ATTITUDE_DATA {
11368 fn default() -> Self {
11369 Self::DEFAULT.clone()
11370 }
11371}
11372impl MessageData for GIMBAL_DEVICE_SET_ATTITUDE_DATA {
11373 type Message = MavMessage;
11374 const ID: u32 = 284u32;
11375 const NAME: &'static str = "GIMBAL_DEVICE_SET_ATTITUDE";
11376 const EXTRA_CRC: u8 = 99u8;
11377 const ENCODED_LEN: usize = 32usize;
11378 fn deser(
11379 _version: MavlinkVersion,
11380 __input: &[u8],
11381 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11382 let avail_len = __input.len();
11383 let mut payload_buf = [0; Self::ENCODED_LEN];
11384 let mut buf = if avail_len < Self::ENCODED_LEN {
11385 payload_buf[0..avail_len].copy_from_slice(__input);
11386 Bytes::new(&payload_buf)
11387 } else {
11388 Bytes::new(__input)
11389 };
11390 let mut __struct = Self::default();
11391 for v in &mut __struct.q {
11392 let val = buf.get_f32_le();
11393 *v = val;
11394 }
11395 __struct.angular_velocity_x = buf.get_f32_le();
11396 __struct.angular_velocity_y = buf.get_f32_le();
11397 __struct.angular_velocity_z = buf.get_f32_le();
11398 let tmp = buf.get_u16_le();
11399 __struct.flags = GimbalDeviceFlags::from_bits(tmp & GimbalDeviceFlags::all().bits())
11400 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
11401 flag_type: "GimbalDeviceFlags",
11402 value: tmp as u32,
11403 })?;
11404 __struct.target_system = buf.get_u8();
11405 __struct.target_component = buf.get_u8();
11406 Ok(__struct)
11407 }
11408 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11409 let mut __tmp = BytesMut::new(bytes);
11410 #[allow(clippy::absurd_extreme_comparisons)]
11411 #[allow(unused_comparisons)]
11412 if __tmp.remaining() < Self::ENCODED_LEN {
11413 panic!(
11414 "buffer is too small (need {} bytes, but got {})",
11415 Self::ENCODED_LEN,
11416 __tmp.remaining(),
11417 )
11418 }
11419 for val in &self.q {
11420 __tmp.put_f32_le(*val);
11421 }
11422 __tmp.put_f32_le(self.angular_velocity_x);
11423 __tmp.put_f32_le(self.angular_velocity_y);
11424 __tmp.put_f32_le(self.angular_velocity_z);
11425 __tmp.put_u16_le(self.flags.bits());
11426 __tmp.put_u8(self.target_system);
11427 __tmp.put_u8(self.target_component);
11428 if matches!(version, MavlinkVersion::V2) {
11429 let len = __tmp.len();
11430 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11431 } else {
11432 __tmp.len()
11433 }
11434 }
11435}
11436#[doc = "id: 324"]
11437#[doc = "Response from a PARAM_EXT_SET message."]
11438#[derive(Debug, Clone, PartialEq)]
11439#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11440#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11441pub struct PARAM_EXT_ACK_DATA {
11442 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
11443 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11444 pub param_id: [u8; 16],
11445 #[doc = "Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)"]
11446 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11447 pub param_value: [u8; 128],
11448 #[doc = "Parameter type."]
11449 pub param_type: MavParamExtType,
11450 #[doc = "Result code."]
11451 pub param_result: ParamAck,
11452}
11453impl PARAM_EXT_ACK_DATA {
11454 pub const ENCODED_LEN: usize = 146usize;
11455 pub const DEFAULT: Self = Self {
11456 param_id: [0_u8; 16usize],
11457 param_value: [0_u8; 128usize],
11458 param_type: MavParamExtType::DEFAULT,
11459 param_result: ParamAck::DEFAULT,
11460 };
11461 #[cfg(feature = "arbitrary")]
11462 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11463 use arbitrary::{Arbitrary, Unstructured};
11464 let mut buf = [0u8; 1024];
11465 rng.fill_bytes(&mut buf);
11466 let mut unstructured = Unstructured::new(&buf);
11467 Self::arbitrary(&mut unstructured).unwrap_or_default()
11468 }
11469}
11470impl Default for PARAM_EXT_ACK_DATA {
11471 fn default() -> Self {
11472 Self::DEFAULT.clone()
11473 }
11474}
11475impl MessageData for PARAM_EXT_ACK_DATA {
11476 type Message = MavMessage;
11477 const ID: u32 = 324u32;
11478 const NAME: &'static str = "PARAM_EXT_ACK";
11479 const EXTRA_CRC: u8 = 132u8;
11480 const ENCODED_LEN: usize = 146usize;
11481 fn deser(
11482 _version: MavlinkVersion,
11483 __input: &[u8],
11484 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11485 let avail_len = __input.len();
11486 let mut payload_buf = [0; Self::ENCODED_LEN];
11487 let mut buf = if avail_len < Self::ENCODED_LEN {
11488 payload_buf[0..avail_len].copy_from_slice(__input);
11489 Bytes::new(&payload_buf)
11490 } else {
11491 Bytes::new(__input)
11492 };
11493 let mut __struct = Self::default();
11494 for v in &mut __struct.param_id {
11495 let val = buf.get_u8();
11496 *v = val;
11497 }
11498 for v in &mut __struct.param_value {
11499 let val = buf.get_u8();
11500 *v = val;
11501 }
11502 let tmp = buf.get_u8();
11503 __struct.param_type =
11504 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11505 enum_type: "MavParamExtType",
11506 value: tmp as u32,
11507 })?;
11508 let tmp = buf.get_u8();
11509 __struct.param_result =
11510 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11511 enum_type: "ParamAck",
11512 value: tmp as u32,
11513 })?;
11514 Ok(__struct)
11515 }
11516 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11517 let mut __tmp = BytesMut::new(bytes);
11518 #[allow(clippy::absurd_extreme_comparisons)]
11519 #[allow(unused_comparisons)]
11520 if __tmp.remaining() < Self::ENCODED_LEN {
11521 panic!(
11522 "buffer is too small (need {} bytes, but got {})",
11523 Self::ENCODED_LEN,
11524 __tmp.remaining(),
11525 )
11526 }
11527 for val in &self.param_id {
11528 __tmp.put_u8(*val);
11529 }
11530 for val in &self.param_value {
11531 __tmp.put_u8(*val);
11532 }
11533 __tmp.put_u8(self.param_type as u8);
11534 __tmp.put_u8(self.param_result as u8);
11535 if matches!(version, MavlinkVersion::V2) {
11536 let len = __tmp.len();
11537 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11538 } else {
11539 __tmp.len()
11540 }
11541 }
11542}
11543#[doc = "id: 54"]
11544#[doc = "Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations."]
11545#[derive(Debug, Clone, PartialEq)]
11546#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11547#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11548pub struct SAFETY_SET_ALLOWED_AREA_DATA {
11549 #[doc = "x position 1 / Latitude 1"]
11550 pub p1x: f32,
11551 #[doc = "y position 1 / Longitude 1"]
11552 pub p1y: f32,
11553 #[doc = "z position 1 / Altitude 1"]
11554 pub p1z: f32,
11555 #[doc = "x position 2 / Latitude 2"]
11556 pub p2x: f32,
11557 #[doc = "y position 2 / Longitude 2"]
11558 pub p2y: f32,
11559 #[doc = "z position 2 / Altitude 2"]
11560 pub p2z: f32,
11561 #[doc = "System ID"]
11562 pub target_system: u8,
11563 #[doc = "Component ID"]
11564 pub target_component: u8,
11565 #[doc = "Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down."]
11566 pub frame: MavFrame,
11567}
11568impl SAFETY_SET_ALLOWED_AREA_DATA {
11569 pub const ENCODED_LEN: usize = 27usize;
11570 pub const DEFAULT: Self = Self {
11571 p1x: 0.0_f32,
11572 p1y: 0.0_f32,
11573 p1z: 0.0_f32,
11574 p2x: 0.0_f32,
11575 p2y: 0.0_f32,
11576 p2z: 0.0_f32,
11577 target_system: 0_u8,
11578 target_component: 0_u8,
11579 frame: MavFrame::DEFAULT,
11580 };
11581 #[cfg(feature = "arbitrary")]
11582 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11583 use arbitrary::{Arbitrary, Unstructured};
11584 let mut buf = [0u8; 1024];
11585 rng.fill_bytes(&mut buf);
11586 let mut unstructured = Unstructured::new(&buf);
11587 Self::arbitrary(&mut unstructured).unwrap_or_default()
11588 }
11589}
11590impl Default for SAFETY_SET_ALLOWED_AREA_DATA {
11591 fn default() -> Self {
11592 Self::DEFAULT.clone()
11593 }
11594}
11595impl MessageData for SAFETY_SET_ALLOWED_AREA_DATA {
11596 type Message = MavMessage;
11597 const ID: u32 = 54u32;
11598 const NAME: &'static str = "SAFETY_SET_ALLOWED_AREA";
11599 const EXTRA_CRC: u8 = 15u8;
11600 const ENCODED_LEN: usize = 27usize;
11601 fn deser(
11602 _version: MavlinkVersion,
11603 __input: &[u8],
11604 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11605 let avail_len = __input.len();
11606 let mut payload_buf = [0; Self::ENCODED_LEN];
11607 let mut buf = if avail_len < Self::ENCODED_LEN {
11608 payload_buf[0..avail_len].copy_from_slice(__input);
11609 Bytes::new(&payload_buf)
11610 } else {
11611 Bytes::new(__input)
11612 };
11613 let mut __struct = Self::default();
11614 __struct.p1x = buf.get_f32_le();
11615 __struct.p1y = buf.get_f32_le();
11616 __struct.p1z = buf.get_f32_le();
11617 __struct.p2x = buf.get_f32_le();
11618 __struct.p2y = buf.get_f32_le();
11619 __struct.p2z = buf.get_f32_le();
11620 __struct.target_system = buf.get_u8();
11621 __struct.target_component = buf.get_u8();
11622 let tmp = buf.get_u8();
11623 __struct.frame =
11624 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11625 enum_type: "MavFrame",
11626 value: tmp as u32,
11627 })?;
11628 Ok(__struct)
11629 }
11630 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11631 let mut __tmp = BytesMut::new(bytes);
11632 #[allow(clippy::absurd_extreme_comparisons)]
11633 #[allow(unused_comparisons)]
11634 if __tmp.remaining() < Self::ENCODED_LEN {
11635 panic!(
11636 "buffer is too small (need {} bytes, but got {})",
11637 Self::ENCODED_LEN,
11638 __tmp.remaining(),
11639 )
11640 }
11641 __tmp.put_f32_le(self.p1x);
11642 __tmp.put_f32_le(self.p1y);
11643 __tmp.put_f32_le(self.p1z);
11644 __tmp.put_f32_le(self.p2x);
11645 __tmp.put_f32_le(self.p2y);
11646 __tmp.put_f32_le(self.p2z);
11647 __tmp.put_u8(self.target_system);
11648 __tmp.put_u8(self.target_component);
11649 __tmp.put_u8(self.frame as u8);
11650 if matches!(version, MavlinkVersion::V2) {
11651 let len = __tmp.len();
11652 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11653 } else {
11654 __tmp.len()
11655 }
11656 }
11657}
11658#[doc = "id: 162"]
11659#[doc = "Status of geo-fencing. Sent in extended status stream when fencing enabled."]
11660#[derive(Debug, Clone, PartialEq)]
11661#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11662#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11663pub struct FENCE_STATUS_DATA {
11664 #[doc = "Time (since boot) of last breach."]
11665 pub breach_time: u32,
11666 #[doc = "Number of fence breaches."]
11667 pub breach_count: u16,
11668 #[doc = "Breach status (0 if currently inside fence, 1 if outside)."]
11669 pub breach_status: u8,
11670 #[doc = "Last breach type."]
11671 pub breach_type: FenceBreach,
11672 #[doc = "Active action to prevent fence breach"]
11673 #[cfg_attr(feature = "serde", serde(default))]
11674 pub breach_mitigation: FenceMitigate,
11675}
11676impl FENCE_STATUS_DATA {
11677 pub const ENCODED_LEN: usize = 9usize;
11678 pub const DEFAULT: Self = Self {
11679 breach_time: 0_u32,
11680 breach_count: 0_u16,
11681 breach_status: 0_u8,
11682 breach_type: FenceBreach::DEFAULT,
11683 breach_mitigation: FenceMitigate::DEFAULT,
11684 };
11685 #[cfg(feature = "arbitrary")]
11686 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11687 use arbitrary::{Arbitrary, Unstructured};
11688 let mut buf = [0u8; 1024];
11689 rng.fill_bytes(&mut buf);
11690 let mut unstructured = Unstructured::new(&buf);
11691 Self::arbitrary(&mut unstructured).unwrap_or_default()
11692 }
11693}
11694impl Default for FENCE_STATUS_DATA {
11695 fn default() -> Self {
11696 Self::DEFAULT.clone()
11697 }
11698}
11699impl MessageData for FENCE_STATUS_DATA {
11700 type Message = MavMessage;
11701 const ID: u32 = 162u32;
11702 const NAME: &'static str = "FENCE_STATUS";
11703 const EXTRA_CRC: u8 = 189u8;
11704 const ENCODED_LEN: usize = 9usize;
11705 fn deser(
11706 _version: MavlinkVersion,
11707 __input: &[u8],
11708 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11709 let avail_len = __input.len();
11710 let mut payload_buf = [0; Self::ENCODED_LEN];
11711 let mut buf = if avail_len < Self::ENCODED_LEN {
11712 payload_buf[0..avail_len].copy_from_slice(__input);
11713 Bytes::new(&payload_buf)
11714 } else {
11715 Bytes::new(__input)
11716 };
11717 let mut __struct = Self::default();
11718 __struct.breach_time = buf.get_u32_le();
11719 __struct.breach_count = buf.get_u16_le();
11720 __struct.breach_status = buf.get_u8();
11721 let tmp = buf.get_u8();
11722 __struct.breach_type =
11723 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11724 enum_type: "FenceBreach",
11725 value: tmp as u32,
11726 })?;
11727 let tmp = buf.get_u8();
11728 __struct.breach_mitigation =
11729 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11730 enum_type: "FenceMitigate",
11731 value: tmp as u32,
11732 })?;
11733 Ok(__struct)
11734 }
11735 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11736 let mut __tmp = BytesMut::new(bytes);
11737 #[allow(clippy::absurd_extreme_comparisons)]
11738 #[allow(unused_comparisons)]
11739 if __tmp.remaining() < Self::ENCODED_LEN {
11740 panic!(
11741 "buffer is too small (need {} bytes, but got {})",
11742 Self::ENCODED_LEN,
11743 __tmp.remaining(),
11744 )
11745 }
11746 __tmp.put_u32_le(self.breach_time);
11747 __tmp.put_u16_le(self.breach_count);
11748 __tmp.put_u8(self.breach_status);
11749 __tmp.put_u8(self.breach_type as u8);
11750 __tmp.put_u8(self.breach_mitigation as u8);
11751 if matches!(version, MavlinkVersion::V2) {
11752 let len = __tmp.len();
11753 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11754 } else {
11755 __tmp.len()
11756 }
11757 }
11758}
11759#[doc = "id: 9005"]
11760#[doc = "Winch status."]
11761#[derive(Debug, Clone, PartialEq)]
11762#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11763#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11764pub struct WINCH_STATUS_DATA {
11765 #[doc = "Timestamp (synced to UNIX time or since system boot)."]
11766 pub time_usec: u64,
11767 #[doc = "Length of line released. NaN if unknown"]
11768 pub line_length: f32,
11769 #[doc = "Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown"]
11770 pub speed: f32,
11771 #[doc = "Tension on the line. NaN if unknown"]
11772 pub tension: f32,
11773 #[doc = "Voltage of the battery supplying the winch. NaN if unknown"]
11774 pub voltage: f32,
11775 #[doc = "Current draw from the winch. NaN if unknown"]
11776 pub current: f32,
11777 #[doc = "Status flags"]
11778 pub status: MavWinchStatusFlag,
11779 #[doc = "Temperature of the motor. INT16_MAX if unknown"]
11780 pub temperature: i16,
11781}
11782impl WINCH_STATUS_DATA {
11783 pub const ENCODED_LEN: usize = 34usize;
11784 pub const DEFAULT: Self = Self {
11785 time_usec: 0_u64,
11786 line_length: 0.0_f32,
11787 speed: 0.0_f32,
11788 tension: 0.0_f32,
11789 voltage: 0.0_f32,
11790 current: 0.0_f32,
11791 status: MavWinchStatusFlag::DEFAULT,
11792 temperature: 0_i16,
11793 };
11794 #[cfg(feature = "arbitrary")]
11795 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11796 use arbitrary::{Arbitrary, Unstructured};
11797 let mut buf = [0u8; 1024];
11798 rng.fill_bytes(&mut buf);
11799 let mut unstructured = Unstructured::new(&buf);
11800 Self::arbitrary(&mut unstructured).unwrap_or_default()
11801 }
11802}
11803impl Default for WINCH_STATUS_DATA {
11804 fn default() -> Self {
11805 Self::DEFAULT.clone()
11806 }
11807}
11808impl MessageData for WINCH_STATUS_DATA {
11809 type Message = MavMessage;
11810 const ID: u32 = 9005u32;
11811 const NAME: &'static str = "WINCH_STATUS";
11812 const EXTRA_CRC: u8 = 117u8;
11813 const ENCODED_LEN: usize = 34usize;
11814 fn deser(
11815 _version: MavlinkVersion,
11816 __input: &[u8],
11817 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11818 let avail_len = __input.len();
11819 let mut payload_buf = [0; Self::ENCODED_LEN];
11820 let mut buf = if avail_len < Self::ENCODED_LEN {
11821 payload_buf[0..avail_len].copy_from_slice(__input);
11822 Bytes::new(&payload_buf)
11823 } else {
11824 Bytes::new(__input)
11825 };
11826 let mut __struct = Self::default();
11827 __struct.time_usec = buf.get_u64_le();
11828 __struct.line_length = buf.get_f32_le();
11829 __struct.speed = buf.get_f32_le();
11830 __struct.tension = buf.get_f32_le();
11831 __struct.voltage = buf.get_f32_le();
11832 __struct.current = buf.get_f32_le();
11833 let tmp = buf.get_u32_le();
11834 __struct.status = MavWinchStatusFlag::from_bits(tmp & MavWinchStatusFlag::all().bits())
11835 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
11836 flag_type: "MavWinchStatusFlag",
11837 value: tmp as u32,
11838 })?;
11839 __struct.temperature = buf.get_i16_le();
11840 Ok(__struct)
11841 }
11842 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11843 let mut __tmp = BytesMut::new(bytes);
11844 #[allow(clippy::absurd_extreme_comparisons)]
11845 #[allow(unused_comparisons)]
11846 if __tmp.remaining() < Self::ENCODED_LEN {
11847 panic!(
11848 "buffer is too small (need {} bytes, but got {})",
11849 Self::ENCODED_LEN,
11850 __tmp.remaining(),
11851 )
11852 }
11853 __tmp.put_u64_le(self.time_usec);
11854 __tmp.put_f32_le(self.line_length);
11855 __tmp.put_f32_le(self.speed);
11856 __tmp.put_f32_le(self.tension);
11857 __tmp.put_f32_le(self.voltage);
11858 __tmp.put_f32_le(self.current);
11859 __tmp.put_u32_le(self.status.bits());
11860 __tmp.put_i16_le(self.temperature);
11861 if matches!(version, MavlinkVersion::V2) {
11862 let len = __tmp.len();
11863 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11864 } else {
11865 __tmp.len()
11866 }
11867 }
11868}
11869#[doc = "id: 290"]
11870#[doc = "ESC information for lower rate streaming. Recommended streaming rate 1Hz. See ESC_STATUS for higher-rate ESC data."]
11871#[derive(Debug, Clone, PartialEq)]
11872#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11873#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11874pub struct ESC_INFO_DATA {
11875 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number."]
11876 pub time_usec: u64,
11877 #[doc = "Number of reported errors by each ESC since boot."]
11878 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11879 pub error_count: [u32; 4],
11880 #[doc = "Counter of data packets received."]
11881 pub counter: u16,
11882 #[doc = "Bitmap of ESC failure flags."]
11883 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11884 pub failure_flags: [u16; 4],
11885 #[doc = "Temperature of each ESC. INT16_MAX: if data not supplied by ESC."]
11886 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11887 pub temperature: [i16; 4],
11888 #[doc = "Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4."]
11889 pub index: u8,
11890 #[doc = "Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data."]
11891 pub count: u8,
11892 #[doc = "Connection type protocol for all ESC."]
11893 pub connection_type: EscConnectionType,
11894 #[doc = "Information regarding online/offline status of each ESC."]
11895 pub info: u8,
11896}
11897impl ESC_INFO_DATA {
11898 pub const ENCODED_LEN: usize = 46usize;
11899 pub const DEFAULT: Self = Self {
11900 time_usec: 0_u64,
11901 error_count: [0_u32; 4usize],
11902 counter: 0_u16,
11903 failure_flags: [0_u16; 4usize],
11904 temperature: [0_i16; 4usize],
11905 index: 0_u8,
11906 count: 0_u8,
11907 connection_type: EscConnectionType::DEFAULT,
11908 info: 0_u8,
11909 };
11910 #[cfg(feature = "arbitrary")]
11911 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11912 use arbitrary::{Arbitrary, Unstructured};
11913 let mut buf = [0u8; 1024];
11914 rng.fill_bytes(&mut buf);
11915 let mut unstructured = Unstructured::new(&buf);
11916 Self::arbitrary(&mut unstructured).unwrap_or_default()
11917 }
11918}
11919impl Default for ESC_INFO_DATA {
11920 fn default() -> Self {
11921 Self::DEFAULT.clone()
11922 }
11923}
11924impl MessageData for ESC_INFO_DATA {
11925 type Message = MavMessage;
11926 const ID: u32 = 290u32;
11927 const NAME: &'static str = "ESC_INFO";
11928 const EXTRA_CRC: u8 = 251u8;
11929 const ENCODED_LEN: usize = 46usize;
11930 fn deser(
11931 _version: MavlinkVersion,
11932 __input: &[u8],
11933 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11934 let avail_len = __input.len();
11935 let mut payload_buf = [0; Self::ENCODED_LEN];
11936 let mut buf = if avail_len < Self::ENCODED_LEN {
11937 payload_buf[0..avail_len].copy_from_slice(__input);
11938 Bytes::new(&payload_buf)
11939 } else {
11940 Bytes::new(__input)
11941 };
11942 let mut __struct = Self::default();
11943 __struct.time_usec = buf.get_u64_le();
11944 for v in &mut __struct.error_count {
11945 let val = buf.get_u32_le();
11946 *v = val;
11947 }
11948 __struct.counter = buf.get_u16_le();
11949 for v in &mut __struct.failure_flags {
11950 let val = buf.get_u16_le();
11951 *v = val;
11952 }
11953 for v in &mut __struct.temperature {
11954 let val = buf.get_i16_le();
11955 *v = val;
11956 }
11957 __struct.index = buf.get_u8();
11958 __struct.count = buf.get_u8();
11959 let tmp = buf.get_u8();
11960 __struct.connection_type =
11961 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11962 enum_type: "EscConnectionType",
11963 value: tmp as u32,
11964 })?;
11965 __struct.info = buf.get_u8();
11966 Ok(__struct)
11967 }
11968 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11969 let mut __tmp = BytesMut::new(bytes);
11970 #[allow(clippy::absurd_extreme_comparisons)]
11971 #[allow(unused_comparisons)]
11972 if __tmp.remaining() < Self::ENCODED_LEN {
11973 panic!(
11974 "buffer is too small (need {} bytes, but got {})",
11975 Self::ENCODED_LEN,
11976 __tmp.remaining(),
11977 )
11978 }
11979 __tmp.put_u64_le(self.time_usec);
11980 for val in &self.error_count {
11981 __tmp.put_u32_le(*val);
11982 }
11983 __tmp.put_u16_le(self.counter);
11984 for val in &self.failure_flags {
11985 __tmp.put_u16_le(*val);
11986 }
11987 for val in &self.temperature {
11988 __tmp.put_i16_le(*val);
11989 }
11990 __tmp.put_u8(self.index);
11991 __tmp.put_u8(self.count);
11992 __tmp.put_u8(self.connection_type as u8);
11993 __tmp.put_u8(self.info);
11994 if matches!(version, MavlinkVersion::V2) {
11995 let len = __tmp.len();
11996 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11997 } else {
11998 __tmp.len()
11999 }
12000 }
12001}
12002#[doc = "id: 37"]
12003#[doc = "Request a partial list of mission items from the system/component. <https://mavlink.io/en/services/mission.html>. If start and end index are the same, just send one waypoint."]
12004#[derive(Debug, Clone, PartialEq)]
12005#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12006#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12007pub struct MISSION_REQUEST_PARTIAL_LIST_DATA {
12008 #[doc = "Start index"]
12009 pub start_index: i16,
12010 #[doc = "End index, -1 by default (-1: send list to end). Else a valid index of the list"]
12011 pub end_index: i16,
12012 #[doc = "System ID"]
12013 pub target_system: u8,
12014 #[doc = "Component ID"]
12015 pub target_component: u8,
12016 #[doc = "Mission type."]
12017 #[cfg_attr(feature = "serde", serde(default))]
12018 pub mission_type: MavMissionType,
12019}
12020impl MISSION_REQUEST_PARTIAL_LIST_DATA {
12021 pub const ENCODED_LEN: usize = 7usize;
12022 pub const DEFAULT: Self = Self {
12023 start_index: 0_i16,
12024 end_index: 0_i16,
12025 target_system: 0_u8,
12026 target_component: 0_u8,
12027 mission_type: MavMissionType::DEFAULT,
12028 };
12029 #[cfg(feature = "arbitrary")]
12030 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12031 use arbitrary::{Arbitrary, Unstructured};
12032 let mut buf = [0u8; 1024];
12033 rng.fill_bytes(&mut buf);
12034 let mut unstructured = Unstructured::new(&buf);
12035 Self::arbitrary(&mut unstructured).unwrap_or_default()
12036 }
12037}
12038impl Default for MISSION_REQUEST_PARTIAL_LIST_DATA {
12039 fn default() -> Self {
12040 Self::DEFAULT.clone()
12041 }
12042}
12043impl MessageData for MISSION_REQUEST_PARTIAL_LIST_DATA {
12044 type Message = MavMessage;
12045 const ID: u32 = 37u32;
12046 const NAME: &'static str = "MISSION_REQUEST_PARTIAL_LIST";
12047 const EXTRA_CRC: u8 = 212u8;
12048 const ENCODED_LEN: usize = 7usize;
12049 fn deser(
12050 _version: MavlinkVersion,
12051 __input: &[u8],
12052 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12053 let avail_len = __input.len();
12054 let mut payload_buf = [0; Self::ENCODED_LEN];
12055 let mut buf = if avail_len < Self::ENCODED_LEN {
12056 payload_buf[0..avail_len].copy_from_slice(__input);
12057 Bytes::new(&payload_buf)
12058 } else {
12059 Bytes::new(__input)
12060 };
12061 let mut __struct = Self::default();
12062 __struct.start_index = buf.get_i16_le();
12063 __struct.end_index = buf.get_i16_le();
12064 __struct.target_system = buf.get_u8();
12065 __struct.target_component = buf.get_u8();
12066 let tmp = buf.get_u8();
12067 __struct.mission_type =
12068 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12069 enum_type: "MavMissionType",
12070 value: tmp as u32,
12071 })?;
12072 Ok(__struct)
12073 }
12074 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12075 let mut __tmp = BytesMut::new(bytes);
12076 #[allow(clippy::absurd_extreme_comparisons)]
12077 #[allow(unused_comparisons)]
12078 if __tmp.remaining() < Self::ENCODED_LEN {
12079 panic!(
12080 "buffer is too small (need {} bytes, but got {})",
12081 Self::ENCODED_LEN,
12082 __tmp.remaining(),
12083 )
12084 }
12085 __tmp.put_i16_le(self.start_index);
12086 __tmp.put_i16_le(self.end_index);
12087 __tmp.put_u8(self.target_system);
12088 __tmp.put_u8(self.target_component);
12089 __tmp.put_u8(self.mission_type as u8);
12090 if matches!(version, MavlinkVersion::V2) {
12091 let len = __tmp.len();
12092 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12093 } else {
12094 __tmp.len()
12095 }
12096 }
12097}
12098#[doc = "id: 62"]
12099#[doc = "The state of the navigation and position controller."]
12100#[derive(Debug, Clone, PartialEq)]
12101#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12102#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12103pub struct NAV_CONTROLLER_OUTPUT_DATA {
12104 #[doc = "Current desired roll"]
12105 pub nav_roll: f32,
12106 #[doc = "Current desired pitch"]
12107 pub nav_pitch: f32,
12108 #[doc = "Current altitude error"]
12109 pub alt_error: f32,
12110 #[doc = "Current airspeed error"]
12111 pub aspd_error: f32,
12112 #[doc = "Current crosstrack error on x-y plane"]
12113 pub xtrack_error: f32,
12114 #[doc = "Current desired heading"]
12115 pub nav_bearing: i16,
12116 #[doc = "Bearing to current waypoint/target"]
12117 pub target_bearing: i16,
12118 #[doc = "Distance to active waypoint"]
12119 pub wp_dist: u16,
12120}
12121impl NAV_CONTROLLER_OUTPUT_DATA {
12122 pub const ENCODED_LEN: usize = 26usize;
12123 pub const DEFAULT: Self = Self {
12124 nav_roll: 0.0_f32,
12125 nav_pitch: 0.0_f32,
12126 alt_error: 0.0_f32,
12127 aspd_error: 0.0_f32,
12128 xtrack_error: 0.0_f32,
12129 nav_bearing: 0_i16,
12130 target_bearing: 0_i16,
12131 wp_dist: 0_u16,
12132 };
12133 #[cfg(feature = "arbitrary")]
12134 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12135 use arbitrary::{Arbitrary, Unstructured};
12136 let mut buf = [0u8; 1024];
12137 rng.fill_bytes(&mut buf);
12138 let mut unstructured = Unstructured::new(&buf);
12139 Self::arbitrary(&mut unstructured).unwrap_or_default()
12140 }
12141}
12142impl Default for NAV_CONTROLLER_OUTPUT_DATA {
12143 fn default() -> Self {
12144 Self::DEFAULT.clone()
12145 }
12146}
12147impl MessageData for NAV_CONTROLLER_OUTPUT_DATA {
12148 type Message = MavMessage;
12149 const ID: u32 = 62u32;
12150 const NAME: &'static str = "NAV_CONTROLLER_OUTPUT";
12151 const EXTRA_CRC: u8 = 183u8;
12152 const ENCODED_LEN: usize = 26usize;
12153 fn deser(
12154 _version: MavlinkVersion,
12155 __input: &[u8],
12156 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12157 let avail_len = __input.len();
12158 let mut payload_buf = [0; Self::ENCODED_LEN];
12159 let mut buf = if avail_len < Self::ENCODED_LEN {
12160 payload_buf[0..avail_len].copy_from_slice(__input);
12161 Bytes::new(&payload_buf)
12162 } else {
12163 Bytes::new(__input)
12164 };
12165 let mut __struct = Self::default();
12166 __struct.nav_roll = buf.get_f32_le();
12167 __struct.nav_pitch = buf.get_f32_le();
12168 __struct.alt_error = buf.get_f32_le();
12169 __struct.aspd_error = buf.get_f32_le();
12170 __struct.xtrack_error = buf.get_f32_le();
12171 __struct.nav_bearing = buf.get_i16_le();
12172 __struct.target_bearing = buf.get_i16_le();
12173 __struct.wp_dist = buf.get_u16_le();
12174 Ok(__struct)
12175 }
12176 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12177 let mut __tmp = BytesMut::new(bytes);
12178 #[allow(clippy::absurd_extreme_comparisons)]
12179 #[allow(unused_comparisons)]
12180 if __tmp.remaining() < Self::ENCODED_LEN {
12181 panic!(
12182 "buffer is too small (need {} bytes, but got {})",
12183 Self::ENCODED_LEN,
12184 __tmp.remaining(),
12185 )
12186 }
12187 __tmp.put_f32_le(self.nav_roll);
12188 __tmp.put_f32_le(self.nav_pitch);
12189 __tmp.put_f32_le(self.alt_error);
12190 __tmp.put_f32_le(self.aspd_error);
12191 __tmp.put_f32_le(self.xtrack_error);
12192 __tmp.put_i16_le(self.nav_bearing);
12193 __tmp.put_i16_le(self.target_bearing);
12194 __tmp.put_u16_le(self.wp_dist);
12195 if matches!(version, MavlinkVersion::V2) {
12196 let len = __tmp.len();
12197 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12198 } else {
12199 __tmp.len()
12200 }
12201 }
12202}
12203#[doc = "id: 114"]
12204#[doc = "Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor)."]
12205#[derive(Debug, Clone, PartialEq)]
12206#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12207#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12208pub struct HIL_OPTICAL_FLOW_DATA {
12209 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
12210 pub time_usec: u64,
12211 #[doc = "Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the."]
12212 pub integration_time_us: u32,
12213 #[doc = "Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)"]
12214 pub integrated_x: f32,
12215 #[doc = "Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)"]
12216 pub integrated_y: f32,
12217 #[doc = "RH rotation around X axis"]
12218 pub integrated_xgyro: f32,
12219 #[doc = "RH rotation around Y axis"]
12220 pub integrated_ygyro: f32,
12221 #[doc = "RH rotation around Z axis"]
12222 pub integrated_zgyro: f32,
12223 #[doc = "Time since the distance was sampled."]
12224 pub time_delta_distance_us: u32,
12225 #[doc = "Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance."]
12226 pub distance: f32,
12227 #[doc = "Temperature"]
12228 pub temperature: i16,
12229 #[doc = "Sensor ID"]
12230 pub sensor_id: u8,
12231 #[doc = "Optical flow quality / confidence. 0: no valid flow, 255: maximum quality"]
12232 pub quality: u8,
12233}
12234impl HIL_OPTICAL_FLOW_DATA {
12235 pub const ENCODED_LEN: usize = 44usize;
12236 pub const DEFAULT: Self = Self {
12237 time_usec: 0_u64,
12238 integration_time_us: 0_u32,
12239 integrated_x: 0.0_f32,
12240 integrated_y: 0.0_f32,
12241 integrated_xgyro: 0.0_f32,
12242 integrated_ygyro: 0.0_f32,
12243 integrated_zgyro: 0.0_f32,
12244 time_delta_distance_us: 0_u32,
12245 distance: 0.0_f32,
12246 temperature: 0_i16,
12247 sensor_id: 0_u8,
12248 quality: 0_u8,
12249 };
12250 #[cfg(feature = "arbitrary")]
12251 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12252 use arbitrary::{Arbitrary, Unstructured};
12253 let mut buf = [0u8; 1024];
12254 rng.fill_bytes(&mut buf);
12255 let mut unstructured = Unstructured::new(&buf);
12256 Self::arbitrary(&mut unstructured).unwrap_or_default()
12257 }
12258}
12259impl Default for HIL_OPTICAL_FLOW_DATA {
12260 fn default() -> Self {
12261 Self::DEFAULT.clone()
12262 }
12263}
12264impl MessageData for HIL_OPTICAL_FLOW_DATA {
12265 type Message = MavMessage;
12266 const ID: u32 = 114u32;
12267 const NAME: &'static str = "HIL_OPTICAL_FLOW";
12268 const EXTRA_CRC: u8 = 237u8;
12269 const ENCODED_LEN: usize = 44usize;
12270 fn deser(
12271 _version: MavlinkVersion,
12272 __input: &[u8],
12273 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12274 let avail_len = __input.len();
12275 let mut payload_buf = [0; Self::ENCODED_LEN];
12276 let mut buf = if avail_len < Self::ENCODED_LEN {
12277 payload_buf[0..avail_len].copy_from_slice(__input);
12278 Bytes::new(&payload_buf)
12279 } else {
12280 Bytes::new(__input)
12281 };
12282 let mut __struct = Self::default();
12283 __struct.time_usec = buf.get_u64_le();
12284 __struct.integration_time_us = buf.get_u32_le();
12285 __struct.integrated_x = buf.get_f32_le();
12286 __struct.integrated_y = buf.get_f32_le();
12287 __struct.integrated_xgyro = buf.get_f32_le();
12288 __struct.integrated_ygyro = buf.get_f32_le();
12289 __struct.integrated_zgyro = buf.get_f32_le();
12290 __struct.time_delta_distance_us = buf.get_u32_le();
12291 __struct.distance = buf.get_f32_le();
12292 __struct.temperature = buf.get_i16_le();
12293 __struct.sensor_id = buf.get_u8();
12294 __struct.quality = buf.get_u8();
12295 Ok(__struct)
12296 }
12297 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12298 let mut __tmp = BytesMut::new(bytes);
12299 #[allow(clippy::absurd_extreme_comparisons)]
12300 #[allow(unused_comparisons)]
12301 if __tmp.remaining() < Self::ENCODED_LEN {
12302 panic!(
12303 "buffer is too small (need {} bytes, but got {})",
12304 Self::ENCODED_LEN,
12305 __tmp.remaining(),
12306 )
12307 }
12308 __tmp.put_u64_le(self.time_usec);
12309 __tmp.put_u32_le(self.integration_time_us);
12310 __tmp.put_f32_le(self.integrated_x);
12311 __tmp.put_f32_le(self.integrated_y);
12312 __tmp.put_f32_le(self.integrated_xgyro);
12313 __tmp.put_f32_le(self.integrated_ygyro);
12314 __tmp.put_f32_le(self.integrated_zgyro);
12315 __tmp.put_u32_le(self.time_delta_distance_us);
12316 __tmp.put_f32_le(self.distance);
12317 __tmp.put_i16_le(self.temperature);
12318 __tmp.put_u8(self.sensor_id);
12319 __tmp.put_u8(self.quality);
12320 if matches!(version, MavlinkVersion::V2) {
12321 let len = __tmp.len();
12322 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12323 } else {
12324 __tmp.len()
12325 }
12326 }
12327}
12328#[doc = "id: 120"]
12329#[doc = "Reply to LOG_REQUEST_DATA."]
12330#[derive(Debug, Clone, PartialEq)]
12331#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12332#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12333pub struct LOG_DATA_DATA {
12334 #[doc = "Offset into the log"]
12335 pub ofs: u32,
12336 #[doc = "Log id (from LOG_ENTRY reply)"]
12337 pub id: u16,
12338 #[doc = "Number of bytes (zero for end of log)"]
12339 pub count: u8,
12340 #[doc = "log data"]
12341 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12342 pub data: [u8; 90],
12343}
12344impl LOG_DATA_DATA {
12345 pub const ENCODED_LEN: usize = 97usize;
12346 pub const DEFAULT: Self = Self {
12347 ofs: 0_u32,
12348 id: 0_u16,
12349 count: 0_u8,
12350 data: [0_u8; 90usize],
12351 };
12352 #[cfg(feature = "arbitrary")]
12353 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12354 use arbitrary::{Arbitrary, Unstructured};
12355 let mut buf = [0u8; 1024];
12356 rng.fill_bytes(&mut buf);
12357 let mut unstructured = Unstructured::new(&buf);
12358 Self::arbitrary(&mut unstructured).unwrap_or_default()
12359 }
12360}
12361impl Default for LOG_DATA_DATA {
12362 fn default() -> Self {
12363 Self::DEFAULT.clone()
12364 }
12365}
12366impl MessageData for LOG_DATA_DATA {
12367 type Message = MavMessage;
12368 const ID: u32 = 120u32;
12369 const NAME: &'static str = "LOG_DATA";
12370 const EXTRA_CRC: u8 = 134u8;
12371 const ENCODED_LEN: usize = 97usize;
12372 fn deser(
12373 _version: MavlinkVersion,
12374 __input: &[u8],
12375 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12376 let avail_len = __input.len();
12377 let mut payload_buf = [0; Self::ENCODED_LEN];
12378 let mut buf = if avail_len < Self::ENCODED_LEN {
12379 payload_buf[0..avail_len].copy_from_slice(__input);
12380 Bytes::new(&payload_buf)
12381 } else {
12382 Bytes::new(__input)
12383 };
12384 let mut __struct = Self::default();
12385 __struct.ofs = buf.get_u32_le();
12386 __struct.id = buf.get_u16_le();
12387 __struct.count = buf.get_u8();
12388 for v in &mut __struct.data {
12389 let val = buf.get_u8();
12390 *v = val;
12391 }
12392 Ok(__struct)
12393 }
12394 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12395 let mut __tmp = BytesMut::new(bytes);
12396 #[allow(clippy::absurd_extreme_comparisons)]
12397 #[allow(unused_comparisons)]
12398 if __tmp.remaining() < Self::ENCODED_LEN {
12399 panic!(
12400 "buffer is too small (need {} bytes, but got {})",
12401 Self::ENCODED_LEN,
12402 __tmp.remaining(),
12403 )
12404 }
12405 __tmp.put_u32_le(self.ofs);
12406 __tmp.put_u16_le(self.id);
12407 __tmp.put_u8(self.count);
12408 for val in &self.data {
12409 __tmp.put_u8(*val);
12410 }
12411 if matches!(version, MavlinkVersion::V2) {
12412 let len = __tmp.len();
12413 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12414 } else {
12415 __tmp.len()
12416 }
12417 }
12418}
12419#[doc = "id: 115"]
12420#[doc = "Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations."]
12421#[derive(Debug, Clone, PartialEq)]
12422#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12423#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12424pub struct HIL_STATE_QUATERNION_DATA {
12425 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
12426 pub time_usec: u64,
12427 #[doc = "Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)"]
12428 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12429 pub attitude_quaternion: [f32; 4],
12430 #[doc = "Body frame roll / phi angular speed"]
12431 pub rollspeed: f32,
12432 #[doc = "Body frame pitch / theta angular speed"]
12433 pub pitchspeed: f32,
12434 #[doc = "Body frame yaw / psi angular speed"]
12435 pub yawspeed: f32,
12436 #[doc = "Latitude"]
12437 pub lat: i32,
12438 #[doc = "Longitude"]
12439 pub lon: i32,
12440 #[doc = "Altitude"]
12441 pub alt: i32,
12442 #[doc = "Ground X Speed (Latitude)"]
12443 pub vx: i16,
12444 #[doc = "Ground Y Speed (Longitude)"]
12445 pub vy: i16,
12446 #[doc = "Ground Z Speed (Altitude)"]
12447 pub vz: i16,
12448 #[doc = "Indicated airspeed"]
12449 pub ind_airspeed: u16,
12450 #[doc = "True airspeed"]
12451 pub true_airspeed: u16,
12452 #[doc = "X acceleration"]
12453 pub xacc: i16,
12454 #[doc = "Y acceleration"]
12455 pub yacc: i16,
12456 #[doc = "Z acceleration"]
12457 pub zacc: i16,
12458}
12459impl HIL_STATE_QUATERNION_DATA {
12460 pub const ENCODED_LEN: usize = 64usize;
12461 pub const DEFAULT: Self = Self {
12462 time_usec: 0_u64,
12463 attitude_quaternion: [0.0_f32; 4usize],
12464 rollspeed: 0.0_f32,
12465 pitchspeed: 0.0_f32,
12466 yawspeed: 0.0_f32,
12467 lat: 0_i32,
12468 lon: 0_i32,
12469 alt: 0_i32,
12470 vx: 0_i16,
12471 vy: 0_i16,
12472 vz: 0_i16,
12473 ind_airspeed: 0_u16,
12474 true_airspeed: 0_u16,
12475 xacc: 0_i16,
12476 yacc: 0_i16,
12477 zacc: 0_i16,
12478 };
12479 #[cfg(feature = "arbitrary")]
12480 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12481 use arbitrary::{Arbitrary, Unstructured};
12482 let mut buf = [0u8; 1024];
12483 rng.fill_bytes(&mut buf);
12484 let mut unstructured = Unstructured::new(&buf);
12485 Self::arbitrary(&mut unstructured).unwrap_or_default()
12486 }
12487}
12488impl Default for HIL_STATE_QUATERNION_DATA {
12489 fn default() -> Self {
12490 Self::DEFAULT.clone()
12491 }
12492}
12493impl MessageData for HIL_STATE_QUATERNION_DATA {
12494 type Message = MavMessage;
12495 const ID: u32 = 115u32;
12496 const NAME: &'static str = "HIL_STATE_QUATERNION";
12497 const EXTRA_CRC: u8 = 4u8;
12498 const ENCODED_LEN: usize = 64usize;
12499 fn deser(
12500 _version: MavlinkVersion,
12501 __input: &[u8],
12502 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12503 let avail_len = __input.len();
12504 let mut payload_buf = [0; Self::ENCODED_LEN];
12505 let mut buf = if avail_len < Self::ENCODED_LEN {
12506 payload_buf[0..avail_len].copy_from_slice(__input);
12507 Bytes::new(&payload_buf)
12508 } else {
12509 Bytes::new(__input)
12510 };
12511 let mut __struct = Self::default();
12512 __struct.time_usec = buf.get_u64_le();
12513 for v in &mut __struct.attitude_quaternion {
12514 let val = buf.get_f32_le();
12515 *v = val;
12516 }
12517 __struct.rollspeed = buf.get_f32_le();
12518 __struct.pitchspeed = buf.get_f32_le();
12519 __struct.yawspeed = buf.get_f32_le();
12520 __struct.lat = buf.get_i32_le();
12521 __struct.lon = buf.get_i32_le();
12522 __struct.alt = buf.get_i32_le();
12523 __struct.vx = buf.get_i16_le();
12524 __struct.vy = buf.get_i16_le();
12525 __struct.vz = buf.get_i16_le();
12526 __struct.ind_airspeed = buf.get_u16_le();
12527 __struct.true_airspeed = buf.get_u16_le();
12528 __struct.xacc = buf.get_i16_le();
12529 __struct.yacc = buf.get_i16_le();
12530 __struct.zacc = buf.get_i16_le();
12531 Ok(__struct)
12532 }
12533 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12534 let mut __tmp = BytesMut::new(bytes);
12535 #[allow(clippy::absurd_extreme_comparisons)]
12536 #[allow(unused_comparisons)]
12537 if __tmp.remaining() < Self::ENCODED_LEN {
12538 panic!(
12539 "buffer is too small (need {} bytes, but got {})",
12540 Self::ENCODED_LEN,
12541 __tmp.remaining(),
12542 )
12543 }
12544 __tmp.put_u64_le(self.time_usec);
12545 for val in &self.attitude_quaternion {
12546 __tmp.put_f32_le(*val);
12547 }
12548 __tmp.put_f32_le(self.rollspeed);
12549 __tmp.put_f32_le(self.pitchspeed);
12550 __tmp.put_f32_le(self.yawspeed);
12551 __tmp.put_i32_le(self.lat);
12552 __tmp.put_i32_le(self.lon);
12553 __tmp.put_i32_le(self.alt);
12554 __tmp.put_i16_le(self.vx);
12555 __tmp.put_i16_le(self.vy);
12556 __tmp.put_i16_le(self.vz);
12557 __tmp.put_u16_le(self.ind_airspeed);
12558 __tmp.put_u16_le(self.true_airspeed);
12559 __tmp.put_i16_le(self.xacc);
12560 __tmp.put_i16_le(self.yacc);
12561 __tmp.put_i16_le(self.zacc);
12562 if matches!(version, MavlinkVersion::V2) {
12563 let len = __tmp.len();
12564 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12565 } else {
12566 __tmp.len()
12567 }
12568 }
12569}
12570#[doc = "id: 436"]
12571#[doc = "Get the current mode. This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). It may be requested using MAV_CMD_REQUEST_MESSAGE. See <https://mavlink.io/en/services/standard_modes.html>."]
12572#[derive(Debug, Clone, PartialEq)]
12573#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12574#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12575pub struct CURRENT_MODE_DATA {
12576 #[doc = "A bitfield for use for autopilot-specific flags"]
12577 pub custom_mode: u32,
12578 #[doc = "The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied"]
12579 pub intended_custom_mode: u32,
12580 #[doc = "Standard mode."]
12581 pub standard_mode: MavStandardMode,
12582}
12583impl CURRENT_MODE_DATA {
12584 pub const ENCODED_LEN: usize = 9usize;
12585 pub const DEFAULT: Self = Self {
12586 custom_mode: 0_u32,
12587 intended_custom_mode: 0_u32,
12588 standard_mode: MavStandardMode::DEFAULT,
12589 };
12590 #[cfg(feature = "arbitrary")]
12591 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12592 use arbitrary::{Arbitrary, Unstructured};
12593 let mut buf = [0u8; 1024];
12594 rng.fill_bytes(&mut buf);
12595 let mut unstructured = Unstructured::new(&buf);
12596 Self::arbitrary(&mut unstructured).unwrap_or_default()
12597 }
12598}
12599impl Default for CURRENT_MODE_DATA {
12600 fn default() -> Self {
12601 Self::DEFAULT.clone()
12602 }
12603}
12604impl MessageData for CURRENT_MODE_DATA {
12605 type Message = MavMessage;
12606 const ID: u32 = 436u32;
12607 const NAME: &'static str = "CURRENT_MODE";
12608 const EXTRA_CRC: u8 = 193u8;
12609 const ENCODED_LEN: usize = 9usize;
12610 fn deser(
12611 _version: MavlinkVersion,
12612 __input: &[u8],
12613 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12614 let avail_len = __input.len();
12615 let mut payload_buf = [0; Self::ENCODED_LEN];
12616 let mut buf = if avail_len < Self::ENCODED_LEN {
12617 payload_buf[0..avail_len].copy_from_slice(__input);
12618 Bytes::new(&payload_buf)
12619 } else {
12620 Bytes::new(__input)
12621 };
12622 let mut __struct = Self::default();
12623 __struct.custom_mode = buf.get_u32_le();
12624 __struct.intended_custom_mode = buf.get_u32_le();
12625 let tmp = buf.get_u8();
12626 __struct.standard_mode =
12627 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12628 enum_type: "MavStandardMode",
12629 value: tmp as u32,
12630 })?;
12631 Ok(__struct)
12632 }
12633 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12634 let mut __tmp = BytesMut::new(bytes);
12635 #[allow(clippy::absurd_extreme_comparisons)]
12636 #[allow(unused_comparisons)]
12637 if __tmp.remaining() < Self::ENCODED_LEN {
12638 panic!(
12639 "buffer is too small (need {} bytes, but got {})",
12640 Self::ENCODED_LEN,
12641 __tmp.remaining(),
12642 )
12643 }
12644 __tmp.put_u32_le(self.custom_mode);
12645 __tmp.put_u32_le(self.intended_custom_mode);
12646 __tmp.put_u8(self.standard_mode as u8);
12647 if matches!(version, MavlinkVersion::V2) {
12648 let len = __tmp.len();
12649 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12650 } else {
12651 __tmp.len()
12652 }
12653 }
12654}
12655#[doc = "id: 9000"]
12656#[doc = "Cumulative distance traveled for each reported wheel."]
12657#[derive(Debug, Clone, PartialEq)]
12658#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12659#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12660pub struct WHEEL_DISTANCE_DATA {
12661 #[doc = "Timestamp (synced to UNIX time or since system boot)."]
12662 pub time_usec: u64,
12663 #[doc = "Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints."]
12664 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12665 pub distance: [f64; 16],
12666 #[doc = "Number of wheels reported."]
12667 pub count: u8,
12668}
12669impl WHEEL_DISTANCE_DATA {
12670 pub const ENCODED_LEN: usize = 137usize;
12671 pub const DEFAULT: Self = Self {
12672 time_usec: 0_u64,
12673 distance: [0.0_f64; 16usize],
12674 count: 0_u8,
12675 };
12676 #[cfg(feature = "arbitrary")]
12677 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12678 use arbitrary::{Arbitrary, Unstructured};
12679 let mut buf = [0u8; 1024];
12680 rng.fill_bytes(&mut buf);
12681 let mut unstructured = Unstructured::new(&buf);
12682 Self::arbitrary(&mut unstructured).unwrap_or_default()
12683 }
12684}
12685impl Default for WHEEL_DISTANCE_DATA {
12686 fn default() -> Self {
12687 Self::DEFAULT.clone()
12688 }
12689}
12690impl MessageData for WHEEL_DISTANCE_DATA {
12691 type Message = MavMessage;
12692 const ID: u32 = 9000u32;
12693 const NAME: &'static str = "WHEEL_DISTANCE";
12694 const EXTRA_CRC: u8 = 113u8;
12695 const ENCODED_LEN: usize = 137usize;
12696 fn deser(
12697 _version: MavlinkVersion,
12698 __input: &[u8],
12699 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12700 let avail_len = __input.len();
12701 let mut payload_buf = [0; Self::ENCODED_LEN];
12702 let mut buf = if avail_len < Self::ENCODED_LEN {
12703 payload_buf[0..avail_len].copy_from_slice(__input);
12704 Bytes::new(&payload_buf)
12705 } else {
12706 Bytes::new(__input)
12707 };
12708 let mut __struct = Self::default();
12709 __struct.time_usec = buf.get_u64_le();
12710 for v in &mut __struct.distance {
12711 let val = buf.get_f64_le();
12712 *v = val;
12713 }
12714 __struct.count = buf.get_u8();
12715 Ok(__struct)
12716 }
12717 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12718 let mut __tmp = BytesMut::new(bytes);
12719 #[allow(clippy::absurd_extreme_comparisons)]
12720 #[allow(unused_comparisons)]
12721 if __tmp.remaining() < Self::ENCODED_LEN {
12722 panic!(
12723 "buffer is too small (need {} bytes, but got {})",
12724 Self::ENCODED_LEN,
12725 __tmp.remaining(),
12726 )
12727 }
12728 __tmp.put_u64_le(self.time_usec);
12729 for val in &self.distance {
12730 __tmp.put_f64_le(*val);
12731 }
12732 __tmp.put_u8(self.count);
12733 if matches!(version, MavlinkVersion::V2) {
12734 let len = __tmp.len();
12735 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12736 } else {
12737 __tmp.len()
12738 }
12739 }
12740}
12741#[doc = "id: 100"]
12742#[doc = "Optical flow from a flow sensor (e.g. optical mouse sensor)."]
12743#[derive(Debug, Clone, PartialEq)]
12744#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12745#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12746pub struct OPTICAL_FLOW_DATA {
12747 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
12748 pub time_usec: u64,
12749 #[doc = "Flow in x-sensor direction, angular-speed compensated"]
12750 pub flow_comp_m_x: f32,
12751 #[doc = "Flow in y-sensor direction, angular-speed compensated"]
12752 pub flow_comp_m_y: f32,
12753 #[doc = "Ground distance. Positive value: distance known. Negative value: Unknown distance"]
12754 pub ground_distance: f32,
12755 #[doc = "Flow in x-sensor direction"]
12756 pub flow_x: i16,
12757 #[doc = "Flow in y-sensor direction"]
12758 pub flow_y: i16,
12759 #[doc = "Sensor ID"]
12760 pub sensor_id: u8,
12761 #[doc = "Optical flow quality / confidence. 0: bad, 255: maximum quality"]
12762 pub quality: u8,
12763 #[doc = "Flow rate about X axis"]
12764 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12765 pub flow_rate_x: f32,
12766 #[doc = "Flow rate about Y axis"]
12767 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12768 pub flow_rate_y: f32,
12769}
12770impl OPTICAL_FLOW_DATA {
12771 pub const ENCODED_LEN: usize = 34usize;
12772 pub const DEFAULT: Self = Self {
12773 time_usec: 0_u64,
12774 flow_comp_m_x: 0.0_f32,
12775 flow_comp_m_y: 0.0_f32,
12776 ground_distance: 0.0_f32,
12777 flow_x: 0_i16,
12778 flow_y: 0_i16,
12779 sensor_id: 0_u8,
12780 quality: 0_u8,
12781 flow_rate_x: 0.0_f32,
12782 flow_rate_y: 0.0_f32,
12783 };
12784 #[cfg(feature = "arbitrary")]
12785 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12786 use arbitrary::{Arbitrary, Unstructured};
12787 let mut buf = [0u8; 1024];
12788 rng.fill_bytes(&mut buf);
12789 let mut unstructured = Unstructured::new(&buf);
12790 Self::arbitrary(&mut unstructured).unwrap_or_default()
12791 }
12792}
12793impl Default for OPTICAL_FLOW_DATA {
12794 fn default() -> Self {
12795 Self::DEFAULT.clone()
12796 }
12797}
12798impl MessageData for OPTICAL_FLOW_DATA {
12799 type Message = MavMessage;
12800 const ID: u32 = 100u32;
12801 const NAME: &'static str = "OPTICAL_FLOW";
12802 const EXTRA_CRC: u8 = 175u8;
12803 const ENCODED_LEN: usize = 34usize;
12804 fn deser(
12805 _version: MavlinkVersion,
12806 __input: &[u8],
12807 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12808 let avail_len = __input.len();
12809 let mut payload_buf = [0; Self::ENCODED_LEN];
12810 let mut buf = if avail_len < Self::ENCODED_LEN {
12811 payload_buf[0..avail_len].copy_from_slice(__input);
12812 Bytes::new(&payload_buf)
12813 } else {
12814 Bytes::new(__input)
12815 };
12816 let mut __struct = Self::default();
12817 __struct.time_usec = buf.get_u64_le();
12818 __struct.flow_comp_m_x = buf.get_f32_le();
12819 __struct.flow_comp_m_y = buf.get_f32_le();
12820 __struct.ground_distance = buf.get_f32_le();
12821 __struct.flow_x = buf.get_i16_le();
12822 __struct.flow_y = buf.get_i16_le();
12823 __struct.sensor_id = buf.get_u8();
12824 __struct.quality = buf.get_u8();
12825 __struct.flow_rate_x = buf.get_f32_le();
12826 __struct.flow_rate_y = buf.get_f32_le();
12827 Ok(__struct)
12828 }
12829 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12830 let mut __tmp = BytesMut::new(bytes);
12831 #[allow(clippy::absurd_extreme_comparisons)]
12832 #[allow(unused_comparisons)]
12833 if __tmp.remaining() < Self::ENCODED_LEN {
12834 panic!(
12835 "buffer is too small (need {} bytes, but got {})",
12836 Self::ENCODED_LEN,
12837 __tmp.remaining(),
12838 )
12839 }
12840 __tmp.put_u64_le(self.time_usec);
12841 __tmp.put_f32_le(self.flow_comp_m_x);
12842 __tmp.put_f32_le(self.flow_comp_m_y);
12843 __tmp.put_f32_le(self.ground_distance);
12844 __tmp.put_i16_le(self.flow_x);
12845 __tmp.put_i16_le(self.flow_y);
12846 __tmp.put_u8(self.sensor_id);
12847 __tmp.put_u8(self.quality);
12848 __tmp.put_f32_le(self.flow_rate_x);
12849 __tmp.put_f32_le(self.flow_rate_y);
12850 if matches!(version, MavlinkVersion::V2) {
12851 let len = __tmp.len();
12852 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12853 } else {
12854 __tmp.len()
12855 }
12856 }
12857}
12858#[doc = "id: 5"]
12859#[doc = "Request to control this MAV."]
12860#[derive(Debug, Clone, PartialEq)]
12861#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12862#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12863pub struct CHANGE_OPERATOR_CONTROL_DATA {
12864 #[doc = "System the GCS requests control for"]
12865 pub target_system: u8,
12866 #[doc = "0: request control of this MAV, 1: Release control of this MAV"]
12867 pub control_request: u8,
12868 #[doc = "0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch."]
12869 pub version: u8,
12870 #[doc = "Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and \"!?,.-\""]
12871 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12872 pub passkey: [u8; 25],
12873}
12874impl CHANGE_OPERATOR_CONTROL_DATA {
12875 pub const ENCODED_LEN: usize = 28usize;
12876 pub const DEFAULT: Self = Self {
12877 target_system: 0_u8,
12878 control_request: 0_u8,
12879 version: 0_u8,
12880 passkey: [0_u8; 25usize],
12881 };
12882 #[cfg(feature = "arbitrary")]
12883 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12884 use arbitrary::{Arbitrary, Unstructured};
12885 let mut buf = [0u8; 1024];
12886 rng.fill_bytes(&mut buf);
12887 let mut unstructured = Unstructured::new(&buf);
12888 Self::arbitrary(&mut unstructured).unwrap_or_default()
12889 }
12890}
12891impl Default for CHANGE_OPERATOR_CONTROL_DATA {
12892 fn default() -> Self {
12893 Self::DEFAULT.clone()
12894 }
12895}
12896impl MessageData for CHANGE_OPERATOR_CONTROL_DATA {
12897 type Message = MavMessage;
12898 const ID: u32 = 5u32;
12899 const NAME: &'static str = "CHANGE_OPERATOR_CONTROL";
12900 const EXTRA_CRC: u8 = 217u8;
12901 const ENCODED_LEN: usize = 28usize;
12902 fn deser(
12903 _version: MavlinkVersion,
12904 __input: &[u8],
12905 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12906 let avail_len = __input.len();
12907 let mut payload_buf = [0; Self::ENCODED_LEN];
12908 let mut buf = if avail_len < Self::ENCODED_LEN {
12909 payload_buf[0..avail_len].copy_from_slice(__input);
12910 Bytes::new(&payload_buf)
12911 } else {
12912 Bytes::new(__input)
12913 };
12914 let mut __struct = Self::default();
12915 __struct.target_system = buf.get_u8();
12916 __struct.control_request = buf.get_u8();
12917 __struct.version = buf.get_u8();
12918 for v in &mut __struct.passkey {
12919 let val = buf.get_u8();
12920 *v = val;
12921 }
12922 Ok(__struct)
12923 }
12924 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12925 let mut __tmp = BytesMut::new(bytes);
12926 #[allow(clippy::absurd_extreme_comparisons)]
12927 #[allow(unused_comparisons)]
12928 if __tmp.remaining() < Self::ENCODED_LEN {
12929 panic!(
12930 "buffer is too small (need {} bytes, but got {})",
12931 Self::ENCODED_LEN,
12932 __tmp.remaining(),
12933 )
12934 }
12935 __tmp.put_u8(self.target_system);
12936 __tmp.put_u8(self.control_request);
12937 __tmp.put_u8(self.version);
12938 for val in &self.passkey {
12939 __tmp.put_u8(*val);
12940 }
12941 if matches!(version, MavlinkVersion::V2) {
12942 let len = __tmp.len();
12943 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12944 } else {
12945 __tmp.len()
12946 }
12947 }
12948}
12949#[doc = "id: 241"]
12950#[doc = "Vibration levels and accelerometer clipping."]
12951#[derive(Debug, Clone, PartialEq)]
12952#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12953#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12954pub struct VIBRATION_DATA {
12955 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
12956 pub time_usec: u64,
12957 #[doc = "Vibration levels on X-axis"]
12958 pub vibration_x: f32,
12959 #[doc = "Vibration levels on Y-axis"]
12960 pub vibration_y: f32,
12961 #[doc = "Vibration levels on Z-axis"]
12962 pub vibration_z: f32,
12963 #[doc = "first accelerometer clipping count"]
12964 pub clipping_0: u32,
12965 #[doc = "second accelerometer clipping count"]
12966 pub clipping_1: u32,
12967 #[doc = "third accelerometer clipping count"]
12968 pub clipping_2: u32,
12969}
12970impl VIBRATION_DATA {
12971 pub const ENCODED_LEN: usize = 32usize;
12972 pub const DEFAULT: Self = Self {
12973 time_usec: 0_u64,
12974 vibration_x: 0.0_f32,
12975 vibration_y: 0.0_f32,
12976 vibration_z: 0.0_f32,
12977 clipping_0: 0_u32,
12978 clipping_1: 0_u32,
12979 clipping_2: 0_u32,
12980 };
12981 #[cfg(feature = "arbitrary")]
12982 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12983 use arbitrary::{Arbitrary, Unstructured};
12984 let mut buf = [0u8; 1024];
12985 rng.fill_bytes(&mut buf);
12986 let mut unstructured = Unstructured::new(&buf);
12987 Self::arbitrary(&mut unstructured).unwrap_or_default()
12988 }
12989}
12990impl Default for VIBRATION_DATA {
12991 fn default() -> Self {
12992 Self::DEFAULT.clone()
12993 }
12994}
12995impl MessageData for VIBRATION_DATA {
12996 type Message = MavMessage;
12997 const ID: u32 = 241u32;
12998 const NAME: &'static str = "VIBRATION";
12999 const EXTRA_CRC: u8 = 90u8;
13000 const ENCODED_LEN: usize = 32usize;
13001 fn deser(
13002 _version: MavlinkVersion,
13003 __input: &[u8],
13004 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13005 let avail_len = __input.len();
13006 let mut payload_buf = [0; Self::ENCODED_LEN];
13007 let mut buf = if avail_len < Self::ENCODED_LEN {
13008 payload_buf[0..avail_len].copy_from_slice(__input);
13009 Bytes::new(&payload_buf)
13010 } else {
13011 Bytes::new(__input)
13012 };
13013 let mut __struct = Self::default();
13014 __struct.time_usec = buf.get_u64_le();
13015 __struct.vibration_x = buf.get_f32_le();
13016 __struct.vibration_y = buf.get_f32_le();
13017 __struct.vibration_z = buf.get_f32_le();
13018 __struct.clipping_0 = buf.get_u32_le();
13019 __struct.clipping_1 = buf.get_u32_le();
13020 __struct.clipping_2 = buf.get_u32_le();
13021 Ok(__struct)
13022 }
13023 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13024 let mut __tmp = BytesMut::new(bytes);
13025 #[allow(clippy::absurd_extreme_comparisons)]
13026 #[allow(unused_comparisons)]
13027 if __tmp.remaining() < Self::ENCODED_LEN {
13028 panic!(
13029 "buffer is too small (need {} bytes, but got {})",
13030 Self::ENCODED_LEN,
13031 __tmp.remaining(),
13032 )
13033 }
13034 __tmp.put_u64_le(self.time_usec);
13035 __tmp.put_f32_le(self.vibration_x);
13036 __tmp.put_f32_le(self.vibration_y);
13037 __tmp.put_f32_le(self.vibration_z);
13038 __tmp.put_u32_le(self.clipping_0);
13039 __tmp.put_u32_le(self.clipping_1);
13040 __tmp.put_u32_le(self.clipping_2);
13041 if matches!(version, MavlinkVersion::V2) {
13042 let len = __tmp.len();
13043 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13044 } else {
13045 __tmp.len()
13046 }
13047 }
13048}
13049#[doc = "id: 271"]
13050#[doc = "Information about the field of view of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
13051#[derive(Debug, Clone, PartialEq)]
13052#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13053#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13054pub struct CAMERA_FOV_STATUS_DATA {
13055 #[doc = "Timestamp (time since system boot)."]
13056 pub time_boot_ms: u32,
13057 #[doc = "Latitude of camera (INT32_MAX if unknown)."]
13058 pub lat_camera: i32,
13059 #[doc = "Longitude of camera (INT32_MAX if unknown)."]
13060 pub lon_camera: i32,
13061 #[doc = "Altitude (MSL) of camera (INT32_MAX if unknown)."]
13062 pub alt_camera: i32,
13063 #[doc = "Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
13064 pub lat_image: i32,
13065 #[doc = "Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
13066 pub lon_image: i32,
13067 #[doc = "Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
13068 pub alt_image: i32,
13069 #[doc = "Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
13070 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13071 pub q: [f32; 4],
13072 #[doc = "Horizontal field of view (NaN if unknown)."]
13073 pub hfov: f32,
13074 #[doc = "Vertical field of view (NaN if unknown)."]
13075 pub vfov: f32,
13076 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
13077 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13078 pub camera_device_id: u8,
13079}
13080impl CAMERA_FOV_STATUS_DATA {
13081 pub const ENCODED_LEN: usize = 53usize;
13082 pub const DEFAULT: Self = Self {
13083 time_boot_ms: 0_u32,
13084 lat_camera: 0_i32,
13085 lon_camera: 0_i32,
13086 alt_camera: 0_i32,
13087 lat_image: 0_i32,
13088 lon_image: 0_i32,
13089 alt_image: 0_i32,
13090 q: [0.0_f32; 4usize],
13091 hfov: 0.0_f32,
13092 vfov: 0.0_f32,
13093 camera_device_id: 0_u8,
13094 };
13095 #[cfg(feature = "arbitrary")]
13096 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13097 use arbitrary::{Arbitrary, Unstructured};
13098 let mut buf = [0u8; 1024];
13099 rng.fill_bytes(&mut buf);
13100 let mut unstructured = Unstructured::new(&buf);
13101 Self::arbitrary(&mut unstructured).unwrap_or_default()
13102 }
13103}
13104impl Default for CAMERA_FOV_STATUS_DATA {
13105 fn default() -> Self {
13106 Self::DEFAULT.clone()
13107 }
13108}
13109impl MessageData for CAMERA_FOV_STATUS_DATA {
13110 type Message = MavMessage;
13111 const ID: u32 = 271u32;
13112 const NAME: &'static str = "CAMERA_FOV_STATUS";
13113 const EXTRA_CRC: u8 = 22u8;
13114 const ENCODED_LEN: usize = 53usize;
13115 fn deser(
13116 _version: MavlinkVersion,
13117 __input: &[u8],
13118 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13119 let avail_len = __input.len();
13120 let mut payload_buf = [0; Self::ENCODED_LEN];
13121 let mut buf = if avail_len < Self::ENCODED_LEN {
13122 payload_buf[0..avail_len].copy_from_slice(__input);
13123 Bytes::new(&payload_buf)
13124 } else {
13125 Bytes::new(__input)
13126 };
13127 let mut __struct = Self::default();
13128 __struct.time_boot_ms = buf.get_u32_le();
13129 __struct.lat_camera = buf.get_i32_le();
13130 __struct.lon_camera = buf.get_i32_le();
13131 __struct.alt_camera = buf.get_i32_le();
13132 __struct.lat_image = buf.get_i32_le();
13133 __struct.lon_image = buf.get_i32_le();
13134 __struct.alt_image = buf.get_i32_le();
13135 for v in &mut __struct.q {
13136 let val = buf.get_f32_le();
13137 *v = val;
13138 }
13139 __struct.hfov = buf.get_f32_le();
13140 __struct.vfov = buf.get_f32_le();
13141 __struct.camera_device_id = buf.get_u8();
13142 Ok(__struct)
13143 }
13144 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13145 let mut __tmp = BytesMut::new(bytes);
13146 #[allow(clippy::absurd_extreme_comparisons)]
13147 #[allow(unused_comparisons)]
13148 if __tmp.remaining() < Self::ENCODED_LEN {
13149 panic!(
13150 "buffer is too small (need {} bytes, but got {})",
13151 Self::ENCODED_LEN,
13152 __tmp.remaining(),
13153 )
13154 }
13155 __tmp.put_u32_le(self.time_boot_ms);
13156 __tmp.put_i32_le(self.lat_camera);
13157 __tmp.put_i32_le(self.lon_camera);
13158 __tmp.put_i32_le(self.alt_camera);
13159 __tmp.put_i32_le(self.lat_image);
13160 __tmp.put_i32_le(self.lon_image);
13161 __tmp.put_i32_le(self.alt_image);
13162 for val in &self.q {
13163 __tmp.put_f32_le(*val);
13164 }
13165 __tmp.put_f32_le(self.hfov);
13166 __tmp.put_f32_le(self.vfov);
13167 __tmp.put_u8(self.camera_device_id);
13168 if matches!(version, MavlinkVersion::V2) {
13169 let len = __tmp.len();
13170 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13171 } else {
13172 __tmp.len()
13173 }
13174 }
13175}
13176#[doc = "id: 44"]
13177#[doc = "This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of waypoints."]
13178#[derive(Debug, Clone, PartialEq)]
13179#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13180#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13181pub struct MISSION_COUNT_DATA {
13182 #[doc = "Number of mission items in the sequence"]
13183 pub count: u16,
13184 #[doc = "System ID"]
13185 pub target_system: u8,
13186 #[doc = "Component ID"]
13187 pub target_component: u8,
13188 #[doc = "Mission type."]
13189 #[cfg_attr(feature = "serde", serde(default))]
13190 pub mission_type: MavMissionType,
13191 #[doc = "Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle). This field is used when downloading a plan from a vehicle to a GCS. 0 on upload to the vehicle from GCS. 0 if plan ids are not supported. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded. The ids are recalculated by the vehicle when any part of the on-vehicle plan changes (when a new plan is uploaded, the vehicle returns the new id to the GCS in MISSION_ACK)."]
13192 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13193 pub opaque_id: u32,
13194}
13195impl MISSION_COUNT_DATA {
13196 pub const ENCODED_LEN: usize = 9usize;
13197 pub const DEFAULT: Self = Self {
13198 count: 0_u16,
13199 target_system: 0_u8,
13200 target_component: 0_u8,
13201 mission_type: MavMissionType::DEFAULT,
13202 opaque_id: 0_u32,
13203 };
13204 #[cfg(feature = "arbitrary")]
13205 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13206 use arbitrary::{Arbitrary, Unstructured};
13207 let mut buf = [0u8; 1024];
13208 rng.fill_bytes(&mut buf);
13209 let mut unstructured = Unstructured::new(&buf);
13210 Self::arbitrary(&mut unstructured).unwrap_or_default()
13211 }
13212}
13213impl Default for MISSION_COUNT_DATA {
13214 fn default() -> Self {
13215 Self::DEFAULT.clone()
13216 }
13217}
13218impl MessageData for MISSION_COUNT_DATA {
13219 type Message = MavMessage;
13220 const ID: u32 = 44u32;
13221 const NAME: &'static str = "MISSION_COUNT";
13222 const EXTRA_CRC: u8 = 221u8;
13223 const ENCODED_LEN: usize = 9usize;
13224 fn deser(
13225 _version: MavlinkVersion,
13226 __input: &[u8],
13227 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13228 let avail_len = __input.len();
13229 let mut payload_buf = [0; Self::ENCODED_LEN];
13230 let mut buf = if avail_len < Self::ENCODED_LEN {
13231 payload_buf[0..avail_len].copy_from_slice(__input);
13232 Bytes::new(&payload_buf)
13233 } else {
13234 Bytes::new(__input)
13235 };
13236 let mut __struct = Self::default();
13237 __struct.count = buf.get_u16_le();
13238 __struct.target_system = buf.get_u8();
13239 __struct.target_component = buf.get_u8();
13240 let tmp = buf.get_u8();
13241 __struct.mission_type =
13242 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13243 enum_type: "MavMissionType",
13244 value: tmp as u32,
13245 })?;
13246 __struct.opaque_id = buf.get_u32_le();
13247 Ok(__struct)
13248 }
13249 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13250 let mut __tmp = BytesMut::new(bytes);
13251 #[allow(clippy::absurd_extreme_comparisons)]
13252 #[allow(unused_comparisons)]
13253 if __tmp.remaining() < Self::ENCODED_LEN {
13254 panic!(
13255 "buffer is too small (need {} bytes, but got {})",
13256 Self::ENCODED_LEN,
13257 __tmp.remaining(),
13258 )
13259 }
13260 __tmp.put_u16_le(self.count);
13261 __tmp.put_u8(self.target_system);
13262 __tmp.put_u8(self.target_component);
13263 __tmp.put_u8(self.mission_type as u8);
13264 __tmp.put_u32_le(self.opaque_id);
13265 if matches!(version, MavlinkVersion::V2) {
13266 let len = __tmp.len();
13267 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13268 } else {
13269 __tmp.len()
13270 }
13271 }
13272}
13273#[doc = "id: 12904"]
13274#[doc = "Data for filling the OpenDroneID System message. The System Message contains general system information including the operator location/altitude and possible aircraft group and/or category/class information."]
13275#[derive(Debug, Clone, PartialEq)]
13276#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13277#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13278pub struct OPEN_DRONE_ID_SYSTEM_DATA {
13279 #[doc = "Latitude of the operator. If unknown: 0 (both Lat/Lon)."]
13280 pub operator_latitude: i32,
13281 #[doc = "Longitude of the operator. If unknown: 0 (both Lat/Lon)."]
13282 pub operator_longitude: i32,
13283 #[doc = "Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA."]
13284 pub area_ceiling: f32,
13285 #[doc = "Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA."]
13286 pub area_floor: f32,
13287 #[doc = "Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m."]
13288 pub operator_altitude_geo: f32,
13289 #[doc = "32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
13290 pub timestamp: u32,
13291 #[doc = "Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA."]
13292 pub area_count: u16,
13293 #[doc = "Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA."]
13294 pub area_radius: u16,
13295 #[doc = "System ID (0 for broadcast)."]
13296 pub target_system: u8,
13297 #[doc = "Component ID (0 for broadcast)."]
13298 pub target_component: u8,
13299 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
13300 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13301 pub id_or_mac: [u8; 20],
13302 #[doc = "Specifies the operator location type."]
13303 pub operator_location_type: MavOdidOperatorLocationType,
13304 #[doc = "Specifies the classification type of the UA."]
13305 pub classification_type: MavOdidClassificationType,
13306 #[doc = "When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA."]
13307 pub category_eu: MavOdidCategoryEu,
13308 #[doc = "When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA."]
13309 pub class_eu: MavOdidClassEu,
13310}
13311impl OPEN_DRONE_ID_SYSTEM_DATA {
13312 pub const ENCODED_LEN: usize = 54usize;
13313 pub const DEFAULT: Self = Self {
13314 operator_latitude: 0_i32,
13315 operator_longitude: 0_i32,
13316 area_ceiling: 0.0_f32,
13317 area_floor: 0.0_f32,
13318 operator_altitude_geo: 0.0_f32,
13319 timestamp: 0_u32,
13320 area_count: 0_u16,
13321 area_radius: 0_u16,
13322 target_system: 0_u8,
13323 target_component: 0_u8,
13324 id_or_mac: [0_u8; 20usize],
13325 operator_location_type: MavOdidOperatorLocationType::DEFAULT,
13326 classification_type: MavOdidClassificationType::DEFAULT,
13327 category_eu: MavOdidCategoryEu::DEFAULT,
13328 class_eu: MavOdidClassEu::DEFAULT,
13329 };
13330 #[cfg(feature = "arbitrary")]
13331 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13332 use arbitrary::{Arbitrary, Unstructured};
13333 let mut buf = [0u8; 1024];
13334 rng.fill_bytes(&mut buf);
13335 let mut unstructured = Unstructured::new(&buf);
13336 Self::arbitrary(&mut unstructured).unwrap_or_default()
13337 }
13338}
13339impl Default for OPEN_DRONE_ID_SYSTEM_DATA {
13340 fn default() -> Self {
13341 Self::DEFAULT.clone()
13342 }
13343}
13344impl MessageData for OPEN_DRONE_ID_SYSTEM_DATA {
13345 type Message = MavMessage;
13346 const ID: u32 = 12904u32;
13347 const NAME: &'static str = "OPEN_DRONE_ID_SYSTEM";
13348 const EXTRA_CRC: u8 = 77u8;
13349 const ENCODED_LEN: usize = 54usize;
13350 fn deser(
13351 _version: MavlinkVersion,
13352 __input: &[u8],
13353 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13354 let avail_len = __input.len();
13355 let mut payload_buf = [0; Self::ENCODED_LEN];
13356 let mut buf = if avail_len < Self::ENCODED_LEN {
13357 payload_buf[0..avail_len].copy_from_slice(__input);
13358 Bytes::new(&payload_buf)
13359 } else {
13360 Bytes::new(__input)
13361 };
13362 let mut __struct = Self::default();
13363 __struct.operator_latitude = buf.get_i32_le();
13364 __struct.operator_longitude = buf.get_i32_le();
13365 __struct.area_ceiling = buf.get_f32_le();
13366 __struct.area_floor = buf.get_f32_le();
13367 __struct.operator_altitude_geo = buf.get_f32_le();
13368 __struct.timestamp = buf.get_u32_le();
13369 __struct.area_count = buf.get_u16_le();
13370 __struct.area_radius = buf.get_u16_le();
13371 __struct.target_system = buf.get_u8();
13372 __struct.target_component = buf.get_u8();
13373 for v in &mut __struct.id_or_mac {
13374 let val = buf.get_u8();
13375 *v = val;
13376 }
13377 let tmp = buf.get_u8();
13378 __struct.operator_location_type =
13379 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13380 enum_type: "MavOdidOperatorLocationType",
13381 value: tmp as u32,
13382 })?;
13383 let tmp = buf.get_u8();
13384 __struct.classification_type =
13385 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13386 enum_type: "MavOdidClassificationType",
13387 value: tmp as u32,
13388 })?;
13389 let tmp = buf.get_u8();
13390 __struct.category_eu =
13391 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13392 enum_type: "MavOdidCategoryEu",
13393 value: tmp as u32,
13394 })?;
13395 let tmp = buf.get_u8();
13396 __struct.class_eu =
13397 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13398 enum_type: "MavOdidClassEu",
13399 value: tmp as u32,
13400 })?;
13401 Ok(__struct)
13402 }
13403 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13404 let mut __tmp = BytesMut::new(bytes);
13405 #[allow(clippy::absurd_extreme_comparisons)]
13406 #[allow(unused_comparisons)]
13407 if __tmp.remaining() < Self::ENCODED_LEN {
13408 panic!(
13409 "buffer is too small (need {} bytes, but got {})",
13410 Self::ENCODED_LEN,
13411 __tmp.remaining(),
13412 )
13413 }
13414 __tmp.put_i32_le(self.operator_latitude);
13415 __tmp.put_i32_le(self.operator_longitude);
13416 __tmp.put_f32_le(self.area_ceiling);
13417 __tmp.put_f32_le(self.area_floor);
13418 __tmp.put_f32_le(self.operator_altitude_geo);
13419 __tmp.put_u32_le(self.timestamp);
13420 __tmp.put_u16_le(self.area_count);
13421 __tmp.put_u16_le(self.area_radius);
13422 __tmp.put_u8(self.target_system);
13423 __tmp.put_u8(self.target_component);
13424 for val in &self.id_or_mac {
13425 __tmp.put_u8(*val);
13426 }
13427 __tmp.put_u8(self.operator_location_type as u8);
13428 __tmp.put_u8(self.classification_type as u8);
13429 __tmp.put_u8(self.category_eu as u8);
13430 __tmp.put_u8(self.class_eu as u8);
13431 if matches!(version, MavlinkVersion::V2) {
13432 let len = __tmp.len();
13433 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13434 } else {
13435 __tmp.len()
13436 }
13437 }
13438}
13439#[doc = "id: 61"]
13440#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)."]
13441#[derive(Debug, Clone, PartialEq)]
13442#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13443#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13444pub struct ATTITUDE_QUATERNION_COV_DATA {
13445 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
13446 pub time_usec: u64,
13447 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)"]
13448 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13449 pub q: [f32; 4],
13450 #[doc = "Roll angular speed"]
13451 pub rollspeed: f32,
13452 #[doc = "Pitch angular speed"]
13453 pub pitchspeed: f32,
13454 #[doc = "Yaw angular speed"]
13455 pub yawspeed: f32,
13456 #[doc = "Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
13457 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13458 pub covariance: [f32; 9],
13459}
13460impl ATTITUDE_QUATERNION_COV_DATA {
13461 pub const ENCODED_LEN: usize = 72usize;
13462 pub const DEFAULT: Self = Self {
13463 time_usec: 0_u64,
13464 q: [0.0_f32; 4usize],
13465 rollspeed: 0.0_f32,
13466 pitchspeed: 0.0_f32,
13467 yawspeed: 0.0_f32,
13468 covariance: [0.0_f32; 9usize],
13469 };
13470 #[cfg(feature = "arbitrary")]
13471 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13472 use arbitrary::{Arbitrary, Unstructured};
13473 let mut buf = [0u8; 1024];
13474 rng.fill_bytes(&mut buf);
13475 let mut unstructured = Unstructured::new(&buf);
13476 Self::arbitrary(&mut unstructured).unwrap_or_default()
13477 }
13478}
13479impl Default for ATTITUDE_QUATERNION_COV_DATA {
13480 fn default() -> Self {
13481 Self::DEFAULT.clone()
13482 }
13483}
13484impl MessageData for ATTITUDE_QUATERNION_COV_DATA {
13485 type Message = MavMessage;
13486 const ID: u32 = 61u32;
13487 const NAME: &'static str = "ATTITUDE_QUATERNION_COV";
13488 const EXTRA_CRC: u8 = 167u8;
13489 const ENCODED_LEN: usize = 72usize;
13490 fn deser(
13491 _version: MavlinkVersion,
13492 __input: &[u8],
13493 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13494 let avail_len = __input.len();
13495 let mut payload_buf = [0; Self::ENCODED_LEN];
13496 let mut buf = if avail_len < Self::ENCODED_LEN {
13497 payload_buf[0..avail_len].copy_from_slice(__input);
13498 Bytes::new(&payload_buf)
13499 } else {
13500 Bytes::new(__input)
13501 };
13502 let mut __struct = Self::default();
13503 __struct.time_usec = buf.get_u64_le();
13504 for v in &mut __struct.q {
13505 let val = buf.get_f32_le();
13506 *v = val;
13507 }
13508 __struct.rollspeed = buf.get_f32_le();
13509 __struct.pitchspeed = buf.get_f32_le();
13510 __struct.yawspeed = buf.get_f32_le();
13511 for v in &mut __struct.covariance {
13512 let val = buf.get_f32_le();
13513 *v = val;
13514 }
13515 Ok(__struct)
13516 }
13517 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13518 let mut __tmp = BytesMut::new(bytes);
13519 #[allow(clippy::absurd_extreme_comparisons)]
13520 #[allow(unused_comparisons)]
13521 if __tmp.remaining() < Self::ENCODED_LEN {
13522 panic!(
13523 "buffer is too small (need {} bytes, but got {})",
13524 Self::ENCODED_LEN,
13525 __tmp.remaining(),
13526 )
13527 }
13528 __tmp.put_u64_le(self.time_usec);
13529 for val in &self.q {
13530 __tmp.put_f32_le(*val);
13531 }
13532 __tmp.put_f32_le(self.rollspeed);
13533 __tmp.put_f32_le(self.pitchspeed);
13534 __tmp.put_f32_le(self.yawspeed);
13535 for val in &self.covariance {
13536 __tmp.put_f32_le(*val);
13537 }
13538 if matches!(version, MavlinkVersion::V2) {
13539 let len = __tmp.len();
13540 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13541 } else {
13542 __tmp.len()
13543 }
13544 }
13545}
13546#[doc = "id: 87"]
13547#[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way."]
13548#[derive(Debug, Clone, PartialEq)]
13549#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13550#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13551pub struct POSITION_TARGET_GLOBAL_INT_DATA {
13552 #[doc = "Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency."]
13553 pub time_boot_ms: u32,
13554 #[doc = "Latitude in WGS84 frame"]
13555 pub lat_int: i32,
13556 #[doc = "Longitude in WGS84 frame"]
13557 pub lon_int: i32,
13558 #[doc = "Altitude (MSL, AGL or relative to home altitude, depending on frame)"]
13559 pub alt: f32,
13560 #[doc = "X velocity in NED frame"]
13561 pub vx: f32,
13562 #[doc = "Y velocity in NED frame"]
13563 pub vy: f32,
13564 #[doc = "Z velocity in NED frame"]
13565 pub vz: f32,
13566 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
13567 pub afx: f32,
13568 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
13569 pub afy: f32,
13570 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
13571 pub afz: f32,
13572 #[doc = "yaw setpoint"]
13573 pub yaw: f32,
13574 #[doc = "yaw rate setpoint"]
13575 pub yaw_rate: f32,
13576 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
13577 pub type_mask: PositionTargetTypemask,
13578 #[doc = "Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)"]
13579 pub coordinate_frame: MavFrame,
13580}
13581impl POSITION_TARGET_GLOBAL_INT_DATA {
13582 pub const ENCODED_LEN: usize = 51usize;
13583 pub const DEFAULT: Self = Self {
13584 time_boot_ms: 0_u32,
13585 lat_int: 0_i32,
13586 lon_int: 0_i32,
13587 alt: 0.0_f32,
13588 vx: 0.0_f32,
13589 vy: 0.0_f32,
13590 vz: 0.0_f32,
13591 afx: 0.0_f32,
13592 afy: 0.0_f32,
13593 afz: 0.0_f32,
13594 yaw: 0.0_f32,
13595 yaw_rate: 0.0_f32,
13596 type_mask: PositionTargetTypemask::DEFAULT,
13597 coordinate_frame: MavFrame::DEFAULT,
13598 };
13599 #[cfg(feature = "arbitrary")]
13600 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13601 use arbitrary::{Arbitrary, Unstructured};
13602 let mut buf = [0u8; 1024];
13603 rng.fill_bytes(&mut buf);
13604 let mut unstructured = Unstructured::new(&buf);
13605 Self::arbitrary(&mut unstructured).unwrap_or_default()
13606 }
13607}
13608impl Default for POSITION_TARGET_GLOBAL_INT_DATA {
13609 fn default() -> Self {
13610 Self::DEFAULT.clone()
13611 }
13612}
13613impl MessageData for POSITION_TARGET_GLOBAL_INT_DATA {
13614 type Message = MavMessage;
13615 const ID: u32 = 87u32;
13616 const NAME: &'static str = "POSITION_TARGET_GLOBAL_INT";
13617 const EXTRA_CRC: u8 = 150u8;
13618 const ENCODED_LEN: usize = 51usize;
13619 fn deser(
13620 _version: MavlinkVersion,
13621 __input: &[u8],
13622 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13623 let avail_len = __input.len();
13624 let mut payload_buf = [0; Self::ENCODED_LEN];
13625 let mut buf = if avail_len < Self::ENCODED_LEN {
13626 payload_buf[0..avail_len].copy_from_slice(__input);
13627 Bytes::new(&payload_buf)
13628 } else {
13629 Bytes::new(__input)
13630 };
13631 let mut __struct = Self::default();
13632 __struct.time_boot_ms = buf.get_u32_le();
13633 __struct.lat_int = buf.get_i32_le();
13634 __struct.lon_int = buf.get_i32_le();
13635 __struct.alt = buf.get_f32_le();
13636 __struct.vx = buf.get_f32_le();
13637 __struct.vy = buf.get_f32_le();
13638 __struct.vz = buf.get_f32_le();
13639 __struct.afx = buf.get_f32_le();
13640 __struct.afy = buf.get_f32_le();
13641 __struct.afz = buf.get_f32_le();
13642 __struct.yaw = buf.get_f32_le();
13643 __struct.yaw_rate = buf.get_f32_le();
13644 let tmp = buf.get_u16_le();
13645 __struct.type_mask = PositionTargetTypemask::from_bits(
13646 tmp & PositionTargetTypemask::all().bits(),
13647 )
13648 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
13649 flag_type: "PositionTargetTypemask",
13650 value: tmp as u32,
13651 })?;
13652 let tmp = buf.get_u8();
13653 __struct.coordinate_frame =
13654 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13655 enum_type: "MavFrame",
13656 value: tmp as u32,
13657 })?;
13658 Ok(__struct)
13659 }
13660 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13661 let mut __tmp = BytesMut::new(bytes);
13662 #[allow(clippy::absurd_extreme_comparisons)]
13663 #[allow(unused_comparisons)]
13664 if __tmp.remaining() < Self::ENCODED_LEN {
13665 panic!(
13666 "buffer is too small (need {} bytes, but got {})",
13667 Self::ENCODED_LEN,
13668 __tmp.remaining(),
13669 )
13670 }
13671 __tmp.put_u32_le(self.time_boot_ms);
13672 __tmp.put_i32_le(self.lat_int);
13673 __tmp.put_i32_le(self.lon_int);
13674 __tmp.put_f32_le(self.alt);
13675 __tmp.put_f32_le(self.vx);
13676 __tmp.put_f32_le(self.vy);
13677 __tmp.put_f32_le(self.vz);
13678 __tmp.put_f32_le(self.afx);
13679 __tmp.put_f32_le(self.afy);
13680 __tmp.put_f32_le(self.afz);
13681 __tmp.put_f32_le(self.yaw);
13682 __tmp.put_f32_le(self.yaw_rate);
13683 __tmp.put_u16_le(self.type_mask.bits());
13684 __tmp.put_u8(self.coordinate_frame as u8);
13685 if matches!(version, MavlinkVersion::V2) {
13686 let len = __tmp.len();
13687 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13688 } else {
13689 __tmp.len()
13690 }
13691 }
13692}
13693#[doc = "id: 139"]
13694#[doc = "Set the vehicle attitude and body angular rates."]
13695#[derive(Debug, Clone, PartialEq)]
13696#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13697#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13698pub struct SET_ACTUATOR_CONTROL_TARGET_DATA {
13699 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
13700 pub time_usec: u64,
13701 #[doc = "Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs."]
13702 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13703 pub controls: [f32; 8],
13704 #[doc = "Actuator group. The \"_mlx\" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances."]
13705 pub group_mlx: u8,
13706 #[doc = "System ID"]
13707 pub target_system: u8,
13708 #[doc = "Component ID"]
13709 pub target_component: u8,
13710}
13711impl SET_ACTUATOR_CONTROL_TARGET_DATA {
13712 pub const ENCODED_LEN: usize = 43usize;
13713 pub const DEFAULT: Self = Self {
13714 time_usec: 0_u64,
13715 controls: [0.0_f32; 8usize],
13716 group_mlx: 0_u8,
13717 target_system: 0_u8,
13718 target_component: 0_u8,
13719 };
13720 #[cfg(feature = "arbitrary")]
13721 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13722 use arbitrary::{Arbitrary, Unstructured};
13723 let mut buf = [0u8; 1024];
13724 rng.fill_bytes(&mut buf);
13725 let mut unstructured = Unstructured::new(&buf);
13726 Self::arbitrary(&mut unstructured).unwrap_or_default()
13727 }
13728}
13729impl Default for SET_ACTUATOR_CONTROL_TARGET_DATA {
13730 fn default() -> Self {
13731 Self::DEFAULT.clone()
13732 }
13733}
13734impl MessageData for SET_ACTUATOR_CONTROL_TARGET_DATA {
13735 type Message = MavMessage;
13736 const ID: u32 = 139u32;
13737 const NAME: &'static str = "SET_ACTUATOR_CONTROL_TARGET";
13738 const EXTRA_CRC: u8 = 168u8;
13739 const ENCODED_LEN: usize = 43usize;
13740 fn deser(
13741 _version: MavlinkVersion,
13742 __input: &[u8],
13743 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13744 let avail_len = __input.len();
13745 let mut payload_buf = [0; Self::ENCODED_LEN];
13746 let mut buf = if avail_len < Self::ENCODED_LEN {
13747 payload_buf[0..avail_len].copy_from_slice(__input);
13748 Bytes::new(&payload_buf)
13749 } else {
13750 Bytes::new(__input)
13751 };
13752 let mut __struct = Self::default();
13753 __struct.time_usec = buf.get_u64_le();
13754 for v in &mut __struct.controls {
13755 let val = buf.get_f32_le();
13756 *v = val;
13757 }
13758 __struct.group_mlx = buf.get_u8();
13759 __struct.target_system = buf.get_u8();
13760 __struct.target_component = buf.get_u8();
13761 Ok(__struct)
13762 }
13763 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13764 let mut __tmp = BytesMut::new(bytes);
13765 #[allow(clippy::absurd_extreme_comparisons)]
13766 #[allow(unused_comparisons)]
13767 if __tmp.remaining() < Self::ENCODED_LEN {
13768 panic!(
13769 "buffer is too small (need {} bytes, but got {})",
13770 Self::ENCODED_LEN,
13771 __tmp.remaining(),
13772 )
13773 }
13774 __tmp.put_u64_le(self.time_usec);
13775 for val in &self.controls {
13776 __tmp.put_f32_le(*val);
13777 }
13778 __tmp.put_u8(self.group_mlx);
13779 __tmp.put_u8(self.target_system);
13780 __tmp.put_u8(self.target_component);
13781 if matches!(version, MavlinkVersion::V2) {
13782 let len = __tmp.len();
13783 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13784 } else {
13785 __tmp.len()
13786 }
13787 }
13788}
13789#[doc = "id: 334"]
13790#[doc = "Report current used cellular network status."]
13791#[derive(Debug, Clone, PartialEq)]
13792#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13793#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13794pub struct CELLULAR_STATUS_DATA {
13795 #[doc = "Mobile country code. If unknown, set to UINT16_MAX"]
13796 pub mcc: u16,
13797 #[doc = "Mobile network code. If unknown, set to UINT16_MAX"]
13798 pub mnc: u16,
13799 #[doc = "Location area code. If unknown, set to 0"]
13800 pub lac: u16,
13801 #[doc = "Cellular modem status"]
13802 pub status: CellularStatusFlag,
13803 #[doc = "Failure reason when status in in CELLULAR_STATUS_FLAG_FAILED"]
13804 pub failure_reason: CellularNetworkFailedReason,
13805 #[doc = "Cellular network radio type: gsm, cdma, lte..."]
13806 pub mavtype: CellularNetworkRadioType,
13807 #[doc = "Signal quality in percent. If unknown, set to UINT8_MAX"]
13808 pub quality: u8,
13809}
13810impl CELLULAR_STATUS_DATA {
13811 pub const ENCODED_LEN: usize = 10usize;
13812 pub const DEFAULT: Self = Self {
13813 mcc: 0_u16,
13814 mnc: 0_u16,
13815 lac: 0_u16,
13816 status: CellularStatusFlag::DEFAULT,
13817 failure_reason: CellularNetworkFailedReason::DEFAULT,
13818 mavtype: CellularNetworkRadioType::DEFAULT,
13819 quality: 0_u8,
13820 };
13821 #[cfg(feature = "arbitrary")]
13822 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13823 use arbitrary::{Arbitrary, Unstructured};
13824 let mut buf = [0u8; 1024];
13825 rng.fill_bytes(&mut buf);
13826 let mut unstructured = Unstructured::new(&buf);
13827 Self::arbitrary(&mut unstructured).unwrap_or_default()
13828 }
13829}
13830impl Default for CELLULAR_STATUS_DATA {
13831 fn default() -> Self {
13832 Self::DEFAULT.clone()
13833 }
13834}
13835impl MessageData for CELLULAR_STATUS_DATA {
13836 type Message = MavMessage;
13837 const ID: u32 = 334u32;
13838 const NAME: &'static str = "CELLULAR_STATUS";
13839 const EXTRA_CRC: u8 = 72u8;
13840 const ENCODED_LEN: usize = 10usize;
13841 fn deser(
13842 _version: MavlinkVersion,
13843 __input: &[u8],
13844 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13845 let avail_len = __input.len();
13846 let mut payload_buf = [0; Self::ENCODED_LEN];
13847 let mut buf = if avail_len < Self::ENCODED_LEN {
13848 payload_buf[0..avail_len].copy_from_slice(__input);
13849 Bytes::new(&payload_buf)
13850 } else {
13851 Bytes::new(__input)
13852 };
13853 let mut __struct = Self::default();
13854 __struct.mcc = buf.get_u16_le();
13855 __struct.mnc = buf.get_u16_le();
13856 __struct.lac = buf.get_u16_le();
13857 let tmp = buf.get_u8();
13858 __struct.status =
13859 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13860 enum_type: "CellularStatusFlag",
13861 value: tmp as u32,
13862 })?;
13863 let tmp = buf.get_u8();
13864 __struct.failure_reason =
13865 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13866 enum_type: "CellularNetworkFailedReason",
13867 value: tmp as u32,
13868 })?;
13869 let tmp = buf.get_u8();
13870 __struct.mavtype =
13871 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13872 enum_type: "CellularNetworkRadioType",
13873 value: tmp as u32,
13874 })?;
13875 __struct.quality = buf.get_u8();
13876 Ok(__struct)
13877 }
13878 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13879 let mut __tmp = BytesMut::new(bytes);
13880 #[allow(clippy::absurd_extreme_comparisons)]
13881 #[allow(unused_comparisons)]
13882 if __tmp.remaining() < Self::ENCODED_LEN {
13883 panic!(
13884 "buffer is too small (need {} bytes, but got {})",
13885 Self::ENCODED_LEN,
13886 __tmp.remaining(),
13887 )
13888 }
13889 __tmp.put_u16_le(self.mcc);
13890 __tmp.put_u16_le(self.mnc);
13891 __tmp.put_u16_le(self.lac);
13892 __tmp.put_u8(self.status as u8);
13893 __tmp.put_u8(self.failure_reason as u8);
13894 __tmp.put_u8(self.mavtype as u8);
13895 __tmp.put_u8(self.quality);
13896 if matches!(version, MavlinkVersion::V2) {
13897 let len = __tmp.len();
13898 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13899 } else {
13900 __tmp.len()
13901 }
13902 }
13903}
13904#[doc = "id: 395"]
13905#[doc = "Component information message, which may be requested using MAV_CMD_REQUEST_MESSAGE."]
13906#[derive(Debug, Clone, PartialEq)]
13907#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13908#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13909pub struct COMPONENT_INFORMATION_DATA {
13910 #[doc = "Timestamp (time since system boot)."]
13911 pub time_boot_ms: u32,
13912 #[doc = "CRC32 of the general metadata file (general_metadata_uri)."]
13913 pub general_metadata_file_crc: u32,
13914 #[doc = "CRC32 of peripherals metadata file (peripherals_metadata_uri)."]
13915 pub peripherals_metadata_file_crc: u32,
13916 #[doc = "MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated."]
13917 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13918 pub general_metadata_uri: [u8; 100],
13919 #[doc = "(Optional) MAVLink FTP URI for the peripherals metadata file (COMP_METADATA_TYPE_PERIPHERALS), which may be compressed with xz. This contains data about \"attached components\" such as UAVCAN nodes. The peripherals are in a separate file because the information must be generated dynamically at runtime. The string needs to be zero terminated."]
13920 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13921 pub peripherals_metadata_uri: [u8; 100],
13922}
13923impl COMPONENT_INFORMATION_DATA {
13924 pub const ENCODED_LEN: usize = 212usize;
13925 pub const DEFAULT: Self = Self {
13926 time_boot_ms: 0_u32,
13927 general_metadata_file_crc: 0_u32,
13928 peripherals_metadata_file_crc: 0_u32,
13929 general_metadata_uri: [0_u8; 100usize],
13930 peripherals_metadata_uri: [0_u8; 100usize],
13931 };
13932 #[cfg(feature = "arbitrary")]
13933 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13934 use arbitrary::{Arbitrary, Unstructured};
13935 let mut buf = [0u8; 1024];
13936 rng.fill_bytes(&mut buf);
13937 let mut unstructured = Unstructured::new(&buf);
13938 Self::arbitrary(&mut unstructured).unwrap_or_default()
13939 }
13940}
13941impl Default for COMPONENT_INFORMATION_DATA {
13942 fn default() -> Self {
13943 Self::DEFAULT.clone()
13944 }
13945}
13946impl MessageData for COMPONENT_INFORMATION_DATA {
13947 type Message = MavMessage;
13948 const ID: u32 = 395u32;
13949 const NAME: &'static str = "COMPONENT_INFORMATION";
13950 const EXTRA_CRC: u8 = 0u8;
13951 const ENCODED_LEN: usize = 212usize;
13952 fn deser(
13953 _version: MavlinkVersion,
13954 __input: &[u8],
13955 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13956 let avail_len = __input.len();
13957 let mut payload_buf = [0; Self::ENCODED_LEN];
13958 let mut buf = if avail_len < Self::ENCODED_LEN {
13959 payload_buf[0..avail_len].copy_from_slice(__input);
13960 Bytes::new(&payload_buf)
13961 } else {
13962 Bytes::new(__input)
13963 };
13964 let mut __struct = Self::default();
13965 __struct.time_boot_ms = buf.get_u32_le();
13966 __struct.general_metadata_file_crc = buf.get_u32_le();
13967 __struct.peripherals_metadata_file_crc = buf.get_u32_le();
13968 for v in &mut __struct.general_metadata_uri {
13969 let val = buf.get_u8();
13970 *v = val;
13971 }
13972 for v in &mut __struct.peripherals_metadata_uri {
13973 let val = buf.get_u8();
13974 *v = val;
13975 }
13976 Ok(__struct)
13977 }
13978 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13979 let mut __tmp = BytesMut::new(bytes);
13980 #[allow(clippy::absurd_extreme_comparisons)]
13981 #[allow(unused_comparisons)]
13982 if __tmp.remaining() < Self::ENCODED_LEN {
13983 panic!(
13984 "buffer is too small (need {} bytes, but got {})",
13985 Self::ENCODED_LEN,
13986 __tmp.remaining(),
13987 )
13988 }
13989 __tmp.put_u32_le(self.time_boot_ms);
13990 __tmp.put_u32_le(self.general_metadata_file_crc);
13991 __tmp.put_u32_le(self.peripherals_metadata_file_crc);
13992 for val in &self.general_metadata_uri {
13993 __tmp.put_u8(*val);
13994 }
13995 for val in &self.peripherals_metadata_uri {
13996 __tmp.put_u8(*val);
13997 }
13998 if matches!(version, MavlinkVersion::V2) {
13999 let len = __tmp.len();
14000 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14001 } else {
14002 __tmp.len()
14003 }
14004 }
14005}
14006#[doc = "id: 109"]
14007#[doc = "Status generated by radio and injected into MAVLink stream."]
14008#[derive(Debug, Clone, PartialEq)]
14009#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14010#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14011pub struct RADIO_STATUS_DATA {
14012 #[doc = "Count of radio packet receive errors (since boot)."]
14013 pub rxerrors: u16,
14014 #[doc = "Count of error corrected radio packets (since boot)."]
14015 pub fixed: u16,
14016 #[doc = "Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
14017 pub rssi: u8,
14018 #[doc = "Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
14019 pub remrssi: u8,
14020 #[doc = "Remaining free transmitter buffer space."]
14021 pub txbuf: u8,
14022 #[doc = "Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown."]
14023 pub noise: u8,
14024 #[doc = "Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown."]
14025 pub remnoise: u8,
14026}
14027impl RADIO_STATUS_DATA {
14028 pub const ENCODED_LEN: usize = 9usize;
14029 pub const DEFAULT: Self = Self {
14030 rxerrors: 0_u16,
14031 fixed: 0_u16,
14032 rssi: 0_u8,
14033 remrssi: 0_u8,
14034 txbuf: 0_u8,
14035 noise: 0_u8,
14036 remnoise: 0_u8,
14037 };
14038 #[cfg(feature = "arbitrary")]
14039 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14040 use arbitrary::{Arbitrary, Unstructured};
14041 let mut buf = [0u8; 1024];
14042 rng.fill_bytes(&mut buf);
14043 let mut unstructured = Unstructured::new(&buf);
14044 Self::arbitrary(&mut unstructured).unwrap_or_default()
14045 }
14046}
14047impl Default for RADIO_STATUS_DATA {
14048 fn default() -> Self {
14049 Self::DEFAULT.clone()
14050 }
14051}
14052impl MessageData for RADIO_STATUS_DATA {
14053 type Message = MavMessage;
14054 const ID: u32 = 109u32;
14055 const NAME: &'static str = "RADIO_STATUS";
14056 const EXTRA_CRC: u8 = 185u8;
14057 const ENCODED_LEN: usize = 9usize;
14058 fn deser(
14059 _version: MavlinkVersion,
14060 __input: &[u8],
14061 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14062 let avail_len = __input.len();
14063 let mut payload_buf = [0; Self::ENCODED_LEN];
14064 let mut buf = if avail_len < Self::ENCODED_LEN {
14065 payload_buf[0..avail_len].copy_from_slice(__input);
14066 Bytes::new(&payload_buf)
14067 } else {
14068 Bytes::new(__input)
14069 };
14070 let mut __struct = Self::default();
14071 __struct.rxerrors = buf.get_u16_le();
14072 __struct.fixed = buf.get_u16_le();
14073 __struct.rssi = buf.get_u8();
14074 __struct.remrssi = buf.get_u8();
14075 __struct.txbuf = buf.get_u8();
14076 __struct.noise = buf.get_u8();
14077 __struct.remnoise = buf.get_u8();
14078 Ok(__struct)
14079 }
14080 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14081 let mut __tmp = BytesMut::new(bytes);
14082 #[allow(clippy::absurd_extreme_comparisons)]
14083 #[allow(unused_comparisons)]
14084 if __tmp.remaining() < Self::ENCODED_LEN {
14085 panic!(
14086 "buffer is too small (need {} bytes, but got {})",
14087 Self::ENCODED_LEN,
14088 __tmp.remaining(),
14089 )
14090 }
14091 __tmp.put_u16_le(self.rxerrors);
14092 __tmp.put_u16_le(self.fixed);
14093 __tmp.put_u8(self.rssi);
14094 __tmp.put_u8(self.remrssi);
14095 __tmp.put_u8(self.txbuf);
14096 __tmp.put_u8(self.noise);
14097 __tmp.put_u8(self.remnoise);
14098 if matches!(version, MavlinkVersion::V2) {
14099 let len = __tmp.len();
14100 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14101 } else {
14102 __tmp.len()
14103 }
14104 }
14105}
14106#[doc = "id: 111"]
14107#[doc = "Time synchronization message. The message is used for both timesync requests and responses. The request is sent with `ts1=syncing component timestamp` and `tc1=0`, and may be broadcast or targeted to a specific system/component. The response is sent with `ts1=syncing component timestamp` (mirror back unchanged), and `tc1=responding component timestamp`, with the `target_system` and `target_component` set to ids of the original request. Systems can determine if they are receiving a request or response based on the value of `tc`. If the response has `target_system==target_component==0` the remote system has not been updated to use the component IDs and cannot reliably timesync; the requestor may report an error. Timestamps are UNIX Epoch time or time since system boot in nanoseconds (the timestamp format can be inferred by checking for the magnitude of the number; generally it doesn't matter as only the offset is used). The message sequence is repeated numerous times with results being filtered/averaged to estimate the offset. See also: <https://mavlink.io/en/services/timesync.html>."]
14108#[derive(Debug, Clone, PartialEq)]
14109#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14110#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14111pub struct TIMESYNC_DATA {
14112 #[doc = "Time sync timestamp 1. Syncing: 0. Responding: Timestamp of responding component."]
14113 pub tc1: i64,
14114 #[doc = "Time sync timestamp 2. Timestamp of syncing component (mirrored in response)."]
14115 pub ts1: i64,
14116 #[doc = "Target system id. Request: 0 (broadcast) or id of specific system. Response must contain system id of the requesting component."]
14117 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14118 pub target_system: u8,
14119 #[doc = "Target component id. Request: 0 (broadcast) or id of specific component. Response must contain component id of the requesting component."]
14120 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14121 pub target_component: u8,
14122}
14123impl TIMESYNC_DATA {
14124 pub const ENCODED_LEN: usize = 18usize;
14125 pub const DEFAULT: Self = Self {
14126 tc1: 0_i64,
14127 ts1: 0_i64,
14128 target_system: 0_u8,
14129 target_component: 0_u8,
14130 };
14131 #[cfg(feature = "arbitrary")]
14132 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14133 use arbitrary::{Arbitrary, Unstructured};
14134 let mut buf = [0u8; 1024];
14135 rng.fill_bytes(&mut buf);
14136 let mut unstructured = Unstructured::new(&buf);
14137 Self::arbitrary(&mut unstructured).unwrap_or_default()
14138 }
14139}
14140impl Default for TIMESYNC_DATA {
14141 fn default() -> Self {
14142 Self::DEFAULT.clone()
14143 }
14144}
14145impl MessageData for TIMESYNC_DATA {
14146 type Message = MavMessage;
14147 const ID: u32 = 111u32;
14148 const NAME: &'static str = "TIMESYNC";
14149 const EXTRA_CRC: u8 = 34u8;
14150 const ENCODED_LEN: usize = 18usize;
14151 fn deser(
14152 _version: MavlinkVersion,
14153 __input: &[u8],
14154 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14155 let avail_len = __input.len();
14156 let mut payload_buf = [0; Self::ENCODED_LEN];
14157 let mut buf = if avail_len < Self::ENCODED_LEN {
14158 payload_buf[0..avail_len].copy_from_slice(__input);
14159 Bytes::new(&payload_buf)
14160 } else {
14161 Bytes::new(__input)
14162 };
14163 let mut __struct = Self::default();
14164 __struct.tc1 = buf.get_i64_le();
14165 __struct.ts1 = buf.get_i64_le();
14166 __struct.target_system = buf.get_u8();
14167 __struct.target_component = buf.get_u8();
14168 Ok(__struct)
14169 }
14170 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14171 let mut __tmp = BytesMut::new(bytes);
14172 #[allow(clippy::absurd_extreme_comparisons)]
14173 #[allow(unused_comparisons)]
14174 if __tmp.remaining() < Self::ENCODED_LEN {
14175 panic!(
14176 "buffer is too small (need {} bytes, but got {})",
14177 Self::ENCODED_LEN,
14178 __tmp.remaining(),
14179 )
14180 }
14181 __tmp.put_i64_le(self.tc1);
14182 __tmp.put_i64_le(self.ts1);
14183 __tmp.put_u8(self.target_system);
14184 __tmp.put_u8(self.target_component);
14185 if matches!(version, MavlinkVersion::V2) {
14186 let len = __tmp.len();
14187 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14188 } else {
14189 __tmp.len()
14190 }
14191 }
14192}
14193#[doc = "id: 281"]
14194#[doc = "Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz)."]
14195#[derive(Debug, Clone, PartialEq)]
14196#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14197#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14198pub struct GIMBAL_MANAGER_STATUS_DATA {
14199 #[doc = "Timestamp (time since system boot)."]
14200 pub time_boot_ms: u32,
14201 #[doc = "High level gimbal manager flags currently applied."]
14202 pub flags: GimbalManagerFlags,
14203 #[doc = "Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal)."]
14204 pub gimbal_device_id: u8,
14205 #[doc = "System ID of MAVLink component with primary control, 0 for none."]
14206 pub primary_control_sysid: u8,
14207 #[doc = "Component ID of MAVLink component with primary control, 0 for none."]
14208 pub primary_control_compid: u8,
14209 #[doc = "System ID of MAVLink component with secondary control, 0 for none."]
14210 pub secondary_control_sysid: u8,
14211 #[doc = "Component ID of MAVLink component with secondary control, 0 for none."]
14212 pub secondary_control_compid: u8,
14213}
14214impl GIMBAL_MANAGER_STATUS_DATA {
14215 pub const ENCODED_LEN: usize = 13usize;
14216 pub const DEFAULT: Self = Self {
14217 time_boot_ms: 0_u32,
14218 flags: GimbalManagerFlags::DEFAULT,
14219 gimbal_device_id: 0_u8,
14220 primary_control_sysid: 0_u8,
14221 primary_control_compid: 0_u8,
14222 secondary_control_sysid: 0_u8,
14223 secondary_control_compid: 0_u8,
14224 };
14225 #[cfg(feature = "arbitrary")]
14226 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14227 use arbitrary::{Arbitrary, Unstructured};
14228 let mut buf = [0u8; 1024];
14229 rng.fill_bytes(&mut buf);
14230 let mut unstructured = Unstructured::new(&buf);
14231 Self::arbitrary(&mut unstructured).unwrap_or_default()
14232 }
14233}
14234impl Default for GIMBAL_MANAGER_STATUS_DATA {
14235 fn default() -> Self {
14236 Self::DEFAULT.clone()
14237 }
14238}
14239impl MessageData for GIMBAL_MANAGER_STATUS_DATA {
14240 type Message = MavMessage;
14241 const ID: u32 = 281u32;
14242 const NAME: &'static str = "GIMBAL_MANAGER_STATUS";
14243 const EXTRA_CRC: u8 = 48u8;
14244 const ENCODED_LEN: usize = 13usize;
14245 fn deser(
14246 _version: MavlinkVersion,
14247 __input: &[u8],
14248 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14249 let avail_len = __input.len();
14250 let mut payload_buf = [0; Self::ENCODED_LEN];
14251 let mut buf = if avail_len < Self::ENCODED_LEN {
14252 payload_buf[0..avail_len].copy_from_slice(__input);
14253 Bytes::new(&payload_buf)
14254 } else {
14255 Bytes::new(__input)
14256 };
14257 let mut __struct = Self::default();
14258 __struct.time_boot_ms = buf.get_u32_le();
14259 let tmp = buf.get_u32_le();
14260 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
14261 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
14262 flag_type: "GimbalManagerFlags",
14263 value: tmp as u32,
14264 })?;
14265 __struct.gimbal_device_id = buf.get_u8();
14266 __struct.primary_control_sysid = buf.get_u8();
14267 __struct.primary_control_compid = buf.get_u8();
14268 __struct.secondary_control_sysid = buf.get_u8();
14269 __struct.secondary_control_compid = buf.get_u8();
14270 Ok(__struct)
14271 }
14272 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14273 let mut __tmp = BytesMut::new(bytes);
14274 #[allow(clippy::absurd_extreme_comparisons)]
14275 #[allow(unused_comparisons)]
14276 if __tmp.remaining() < Self::ENCODED_LEN {
14277 panic!(
14278 "buffer is too small (need {} bytes, but got {})",
14279 Self::ENCODED_LEN,
14280 __tmp.remaining(),
14281 )
14282 }
14283 __tmp.put_u32_le(self.time_boot_ms);
14284 __tmp.put_u32_le(self.flags.bits());
14285 __tmp.put_u8(self.gimbal_device_id);
14286 __tmp.put_u8(self.primary_control_sysid);
14287 __tmp.put_u8(self.primary_control_compid);
14288 __tmp.put_u8(self.secondary_control_sysid);
14289 __tmp.put_u8(self.secondary_control_compid);
14290 if matches!(version, MavlinkVersion::V2) {
14291 let len = __tmp.len();
14292 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14293 } else {
14294 __tmp.len()
14295 }
14296 }
14297}
14298#[doc = "id: 80"]
14299#[doc = "Cancel a long running command. The target system should respond with a COMMAND_ACK to the original command with result=MAV_RESULT_CANCELLED if the long running process was cancelled. If it has already completed, the cancel action can be ignored. The cancel action can be retried until some sort of acknowledgement to the original command has been received. The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
14300#[derive(Debug, Clone, PartialEq)]
14301#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14302#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14303pub struct COMMAND_CANCEL_DATA {
14304 #[doc = "Command ID (of command to cancel)."]
14305 pub command: MavCmd,
14306 #[doc = "System executing long running command. Should not be broadcast (0)."]
14307 pub target_system: u8,
14308 #[doc = "Component executing long running command."]
14309 pub target_component: u8,
14310}
14311impl COMMAND_CANCEL_DATA {
14312 pub const ENCODED_LEN: usize = 4usize;
14313 pub const DEFAULT: Self = Self {
14314 command: MavCmd::DEFAULT,
14315 target_system: 0_u8,
14316 target_component: 0_u8,
14317 };
14318 #[cfg(feature = "arbitrary")]
14319 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14320 use arbitrary::{Arbitrary, Unstructured};
14321 let mut buf = [0u8; 1024];
14322 rng.fill_bytes(&mut buf);
14323 let mut unstructured = Unstructured::new(&buf);
14324 Self::arbitrary(&mut unstructured).unwrap_or_default()
14325 }
14326}
14327impl Default for COMMAND_CANCEL_DATA {
14328 fn default() -> Self {
14329 Self::DEFAULT.clone()
14330 }
14331}
14332impl MessageData for COMMAND_CANCEL_DATA {
14333 type Message = MavMessage;
14334 const ID: u32 = 80u32;
14335 const NAME: &'static str = "COMMAND_CANCEL";
14336 const EXTRA_CRC: u8 = 14u8;
14337 const ENCODED_LEN: usize = 4usize;
14338 fn deser(
14339 _version: MavlinkVersion,
14340 __input: &[u8],
14341 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14342 let avail_len = __input.len();
14343 let mut payload_buf = [0; Self::ENCODED_LEN];
14344 let mut buf = if avail_len < Self::ENCODED_LEN {
14345 payload_buf[0..avail_len].copy_from_slice(__input);
14346 Bytes::new(&payload_buf)
14347 } else {
14348 Bytes::new(__input)
14349 };
14350 let mut __struct = Self::default();
14351 let tmp = buf.get_u16_le();
14352 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
14353 ::mavlink_core::error::ParserError::InvalidEnum {
14354 enum_type: "MavCmd",
14355 value: tmp as u32,
14356 },
14357 )?;
14358 __struct.target_system = buf.get_u8();
14359 __struct.target_component = buf.get_u8();
14360 Ok(__struct)
14361 }
14362 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14363 let mut __tmp = BytesMut::new(bytes);
14364 #[allow(clippy::absurd_extreme_comparisons)]
14365 #[allow(unused_comparisons)]
14366 if __tmp.remaining() < Self::ENCODED_LEN {
14367 panic!(
14368 "buffer is too small (need {} bytes, but got {})",
14369 Self::ENCODED_LEN,
14370 __tmp.remaining(),
14371 )
14372 }
14373 __tmp.put_u16_le(self.command as u16);
14374 __tmp.put_u8(self.target_system);
14375 __tmp.put_u8(self.target_component);
14376 if matches!(version, MavlinkVersion::V2) {
14377 let len = __tmp.len();
14378 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14379 } else {
14380 __tmp.len()
14381 }
14382 }
14383}
14384#[doc = "id: 93"]
14385#[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to HIL_CONTROLS."]
14386#[derive(Debug, Clone, PartialEq)]
14387#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14388#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14389pub struct HIL_ACTUATOR_CONTROLS_DATA {
14390 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
14391 pub time_usec: u64,
14392 #[doc = "Flags bitmask."]
14393 pub flags: HilActuatorControlsFlags,
14394 #[doc = "Control outputs -1 .. 1. Channel assignment depends on the simulated hardware."]
14395 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14396 pub controls: [f32; 16],
14397 #[doc = "System mode. Includes arming state."]
14398 pub mode: MavModeFlag,
14399}
14400impl HIL_ACTUATOR_CONTROLS_DATA {
14401 pub const ENCODED_LEN: usize = 81usize;
14402 pub const DEFAULT: Self = Self {
14403 time_usec: 0_u64,
14404 flags: HilActuatorControlsFlags::DEFAULT,
14405 controls: [0.0_f32; 16usize],
14406 mode: MavModeFlag::DEFAULT,
14407 };
14408 #[cfg(feature = "arbitrary")]
14409 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14410 use arbitrary::{Arbitrary, Unstructured};
14411 let mut buf = [0u8; 1024];
14412 rng.fill_bytes(&mut buf);
14413 let mut unstructured = Unstructured::new(&buf);
14414 Self::arbitrary(&mut unstructured).unwrap_or_default()
14415 }
14416}
14417impl Default for HIL_ACTUATOR_CONTROLS_DATA {
14418 fn default() -> Self {
14419 Self::DEFAULT.clone()
14420 }
14421}
14422impl MessageData for HIL_ACTUATOR_CONTROLS_DATA {
14423 type Message = MavMessage;
14424 const ID: u32 = 93u32;
14425 const NAME: &'static str = "HIL_ACTUATOR_CONTROLS";
14426 const EXTRA_CRC: u8 = 47u8;
14427 const ENCODED_LEN: usize = 81usize;
14428 fn deser(
14429 _version: MavlinkVersion,
14430 __input: &[u8],
14431 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14432 let avail_len = __input.len();
14433 let mut payload_buf = [0; Self::ENCODED_LEN];
14434 let mut buf = if avail_len < Self::ENCODED_LEN {
14435 payload_buf[0..avail_len].copy_from_slice(__input);
14436 Bytes::new(&payload_buf)
14437 } else {
14438 Bytes::new(__input)
14439 };
14440 let mut __struct = Self::default();
14441 __struct.time_usec = buf.get_u64_le();
14442 let tmp = buf.get_u64_le();
14443 __struct.flags =
14444 HilActuatorControlsFlags::from_bits(tmp & HilActuatorControlsFlags::all().bits())
14445 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
14446 flag_type: "HilActuatorControlsFlags",
14447 value: tmp as u32,
14448 })?;
14449 for v in &mut __struct.controls {
14450 let val = buf.get_f32_le();
14451 *v = val;
14452 }
14453 let tmp = buf.get_u8();
14454 __struct.mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
14455 ::mavlink_core::error::ParserError::InvalidFlag {
14456 flag_type: "MavModeFlag",
14457 value: tmp as u32,
14458 },
14459 )?;
14460 Ok(__struct)
14461 }
14462 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14463 let mut __tmp = BytesMut::new(bytes);
14464 #[allow(clippy::absurd_extreme_comparisons)]
14465 #[allow(unused_comparisons)]
14466 if __tmp.remaining() < Self::ENCODED_LEN {
14467 panic!(
14468 "buffer is too small (need {} bytes, but got {})",
14469 Self::ENCODED_LEN,
14470 __tmp.remaining(),
14471 )
14472 }
14473 __tmp.put_u64_le(self.time_usec);
14474 __tmp.put_u64_le(self.flags.bits());
14475 for val in &self.controls {
14476 __tmp.put_f32_le(*val);
14477 }
14478 __tmp.put_u8(self.mode.bits());
14479 if matches!(version, MavlinkVersion::V2) {
14480 let len = __tmp.len();
14481 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14482 } else {
14483 __tmp.len()
14484 }
14485 }
14486}
14487#[doc = "id: 252"]
14488#[doc = "Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
14489#[derive(Debug, Clone, PartialEq)]
14490#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14491#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14492pub struct NAMED_VALUE_INT_DATA {
14493 #[doc = "Timestamp (time since system boot)."]
14494 pub time_boot_ms: u32,
14495 #[doc = "Signed integer value"]
14496 pub value: i32,
14497 #[doc = "Name of the debug variable"]
14498 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14499 pub name: [u8; 10],
14500}
14501impl NAMED_VALUE_INT_DATA {
14502 pub const ENCODED_LEN: usize = 18usize;
14503 pub const DEFAULT: Self = Self {
14504 time_boot_ms: 0_u32,
14505 value: 0_i32,
14506 name: [0_u8; 10usize],
14507 };
14508 #[cfg(feature = "arbitrary")]
14509 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14510 use arbitrary::{Arbitrary, Unstructured};
14511 let mut buf = [0u8; 1024];
14512 rng.fill_bytes(&mut buf);
14513 let mut unstructured = Unstructured::new(&buf);
14514 Self::arbitrary(&mut unstructured).unwrap_or_default()
14515 }
14516}
14517impl Default for NAMED_VALUE_INT_DATA {
14518 fn default() -> Self {
14519 Self::DEFAULT.clone()
14520 }
14521}
14522impl MessageData for NAMED_VALUE_INT_DATA {
14523 type Message = MavMessage;
14524 const ID: u32 = 252u32;
14525 const NAME: &'static str = "NAMED_VALUE_INT";
14526 const EXTRA_CRC: u8 = 44u8;
14527 const ENCODED_LEN: usize = 18usize;
14528 fn deser(
14529 _version: MavlinkVersion,
14530 __input: &[u8],
14531 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14532 let avail_len = __input.len();
14533 let mut payload_buf = [0; Self::ENCODED_LEN];
14534 let mut buf = if avail_len < Self::ENCODED_LEN {
14535 payload_buf[0..avail_len].copy_from_slice(__input);
14536 Bytes::new(&payload_buf)
14537 } else {
14538 Bytes::new(__input)
14539 };
14540 let mut __struct = Self::default();
14541 __struct.time_boot_ms = buf.get_u32_le();
14542 __struct.value = buf.get_i32_le();
14543 for v in &mut __struct.name {
14544 let val = buf.get_u8();
14545 *v = val;
14546 }
14547 Ok(__struct)
14548 }
14549 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14550 let mut __tmp = BytesMut::new(bytes);
14551 #[allow(clippy::absurd_extreme_comparisons)]
14552 #[allow(unused_comparisons)]
14553 if __tmp.remaining() < Self::ENCODED_LEN {
14554 panic!(
14555 "buffer is too small (need {} bytes, but got {})",
14556 Self::ENCODED_LEN,
14557 __tmp.remaining(),
14558 )
14559 }
14560 __tmp.put_u32_le(self.time_boot_ms);
14561 __tmp.put_i32_le(self.value);
14562 for val in &self.name {
14563 __tmp.put_u8(*val);
14564 }
14565 if matches!(version, MavlinkVersion::V2) {
14566 let len = __tmp.len();
14567 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14568 } else {
14569 __tmp.len()
14570 }
14571 }
14572}
14573#[doc = "id: 350"]
14574#[doc = "Large debug/prototyping array. The message uses the maximum available payload for data. The array_id and name fields are used to discriminate between messages in code and in user interfaces (respectively). Do not use in production code."]
14575#[derive(Debug, Clone, PartialEq)]
14576#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14577#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14578pub struct DEBUG_FLOAT_ARRAY_DATA {
14579 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
14580 pub time_usec: u64,
14581 #[doc = "Unique ID used to discriminate between arrays"]
14582 pub array_id: u16,
14583 #[doc = "Name, for human-friendly display in a Ground Control Station"]
14584 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14585 pub name: [u8; 10],
14586 #[doc = "data"]
14587 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14588 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14589 pub data: [f32; 58],
14590}
14591impl DEBUG_FLOAT_ARRAY_DATA {
14592 pub const ENCODED_LEN: usize = 252usize;
14593 pub const DEFAULT: Self = Self {
14594 time_usec: 0_u64,
14595 array_id: 0_u16,
14596 name: [0_u8; 10usize],
14597 data: [0.0_f32; 58usize],
14598 };
14599 #[cfg(feature = "arbitrary")]
14600 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14601 use arbitrary::{Arbitrary, Unstructured};
14602 let mut buf = [0u8; 1024];
14603 rng.fill_bytes(&mut buf);
14604 let mut unstructured = Unstructured::new(&buf);
14605 Self::arbitrary(&mut unstructured).unwrap_or_default()
14606 }
14607}
14608impl Default for DEBUG_FLOAT_ARRAY_DATA {
14609 fn default() -> Self {
14610 Self::DEFAULT.clone()
14611 }
14612}
14613impl MessageData for DEBUG_FLOAT_ARRAY_DATA {
14614 type Message = MavMessage;
14615 const ID: u32 = 350u32;
14616 const NAME: &'static str = "DEBUG_FLOAT_ARRAY";
14617 const EXTRA_CRC: u8 = 232u8;
14618 const ENCODED_LEN: usize = 252usize;
14619 fn deser(
14620 _version: MavlinkVersion,
14621 __input: &[u8],
14622 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14623 let avail_len = __input.len();
14624 let mut payload_buf = [0; Self::ENCODED_LEN];
14625 let mut buf = if avail_len < Self::ENCODED_LEN {
14626 payload_buf[0..avail_len].copy_from_slice(__input);
14627 Bytes::new(&payload_buf)
14628 } else {
14629 Bytes::new(__input)
14630 };
14631 let mut __struct = Self::default();
14632 __struct.time_usec = buf.get_u64_le();
14633 __struct.array_id = buf.get_u16_le();
14634 for v in &mut __struct.name {
14635 let val = buf.get_u8();
14636 *v = val;
14637 }
14638 for v in &mut __struct.data {
14639 let val = buf.get_f32_le();
14640 *v = val;
14641 }
14642 Ok(__struct)
14643 }
14644 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14645 let mut __tmp = BytesMut::new(bytes);
14646 #[allow(clippy::absurd_extreme_comparisons)]
14647 #[allow(unused_comparisons)]
14648 if __tmp.remaining() < Self::ENCODED_LEN {
14649 panic!(
14650 "buffer is too small (need {} bytes, but got {})",
14651 Self::ENCODED_LEN,
14652 __tmp.remaining(),
14653 )
14654 }
14655 __tmp.put_u64_le(self.time_usec);
14656 __tmp.put_u16_le(self.array_id);
14657 for val in &self.name {
14658 __tmp.put_u8(*val);
14659 }
14660 for val in &self.data {
14661 __tmp.put_f32_le(*val);
14662 }
14663 if matches!(version, MavlinkVersion::V2) {
14664 let len = __tmp.len();
14665 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14666 } else {
14667 __tmp.len()
14668 }
14669 }
14670}
14671#[doc = "id: 12900"]
14672#[doc = "Data for filling the OpenDroneID Basic ID message. This and the below messages are primarily meant for feeding data to/from an OpenDroneID implementation. E.g. <https://github.com/opendroneid/opendroneid-core-c>. These messages are compatible with the ASTM F3411 Remote ID standard and the ASD-STAN prEN 4709-002 Direct Remote ID standard. Additional information and usage of these messages is documented at <https://mavlink.io/en/services/opendroneid.html>."]
14673#[derive(Debug, Clone, PartialEq)]
14674#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14675#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14676pub struct OPEN_DRONE_ID_BASIC_ID_DATA {
14677 #[doc = "System ID (0 for broadcast)."]
14678 pub target_system: u8,
14679 #[doc = "Component ID (0 for broadcast)."]
14680 pub target_component: u8,
14681 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
14682 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14683 pub id_or_mac: [u8; 20],
14684 #[doc = "Indicates the format for the uas_id field of this message."]
14685 pub id_type: MavOdidIdType,
14686 #[doc = "Indicates the type of UA (Unmanned Aircraft)."]
14687 pub ua_type: MavOdidUaType,
14688 #[doc = "UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field."]
14689 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14690 pub uas_id: [u8; 20],
14691}
14692impl OPEN_DRONE_ID_BASIC_ID_DATA {
14693 pub const ENCODED_LEN: usize = 44usize;
14694 pub const DEFAULT: Self = Self {
14695 target_system: 0_u8,
14696 target_component: 0_u8,
14697 id_or_mac: [0_u8; 20usize],
14698 id_type: MavOdidIdType::DEFAULT,
14699 ua_type: MavOdidUaType::DEFAULT,
14700 uas_id: [0_u8; 20usize],
14701 };
14702 #[cfg(feature = "arbitrary")]
14703 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14704 use arbitrary::{Arbitrary, Unstructured};
14705 let mut buf = [0u8; 1024];
14706 rng.fill_bytes(&mut buf);
14707 let mut unstructured = Unstructured::new(&buf);
14708 Self::arbitrary(&mut unstructured).unwrap_or_default()
14709 }
14710}
14711impl Default for OPEN_DRONE_ID_BASIC_ID_DATA {
14712 fn default() -> Self {
14713 Self::DEFAULT.clone()
14714 }
14715}
14716impl MessageData for OPEN_DRONE_ID_BASIC_ID_DATA {
14717 type Message = MavMessage;
14718 const ID: u32 = 12900u32;
14719 const NAME: &'static str = "OPEN_DRONE_ID_BASIC_ID";
14720 const EXTRA_CRC: u8 = 114u8;
14721 const ENCODED_LEN: usize = 44usize;
14722 fn deser(
14723 _version: MavlinkVersion,
14724 __input: &[u8],
14725 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14726 let avail_len = __input.len();
14727 let mut payload_buf = [0; Self::ENCODED_LEN];
14728 let mut buf = if avail_len < Self::ENCODED_LEN {
14729 payload_buf[0..avail_len].copy_from_slice(__input);
14730 Bytes::new(&payload_buf)
14731 } else {
14732 Bytes::new(__input)
14733 };
14734 let mut __struct = Self::default();
14735 __struct.target_system = buf.get_u8();
14736 __struct.target_component = buf.get_u8();
14737 for v in &mut __struct.id_or_mac {
14738 let val = buf.get_u8();
14739 *v = val;
14740 }
14741 let tmp = buf.get_u8();
14742 __struct.id_type =
14743 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14744 enum_type: "MavOdidIdType",
14745 value: tmp as u32,
14746 })?;
14747 let tmp = buf.get_u8();
14748 __struct.ua_type =
14749 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14750 enum_type: "MavOdidUaType",
14751 value: tmp as u32,
14752 })?;
14753 for v in &mut __struct.uas_id {
14754 let val = buf.get_u8();
14755 *v = val;
14756 }
14757 Ok(__struct)
14758 }
14759 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14760 let mut __tmp = BytesMut::new(bytes);
14761 #[allow(clippy::absurd_extreme_comparisons)]
14762 #[allow(unused_comparisons)]
14763 if __tmp.remaining() < Self::ENCODED_LEN {
14764 panic!(
14765 "buffer is too small (need {} bytes, but got {})",
14766 Self::ENCODED_LEN,
14767 __tmp.remaining(),
14768 )
14769 }
14770 __tmp.put_u8(self.target_system);
14771 __tmp.put_u8(self.target_component);
14772 for val in &self.id_or_mac {
14773 __tmp.put_u8(*val);
14774 }
14775 __tmp.put_u8(self.id_type as u8);
14776 __tmp.put_u8(self.ua_type as u8);
14777 for val in &self.uas_id {
14778 __tmp.put_u8(*val);
14779 }
14780 if matches!(version, MavlinkVersion::V2) {
14781 let len = __tmp.len();
14782 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14783 } else {
14784 __tmp.len()
14785 }
14786 }
14787}
14788#[doc = "id: 397"]
14789#[doc = "Component metadata message, which may be requested using MAV_CMD_REQUEST_MESSAGE. This contains the MAVLink FTP URI and CRC for the component's general metadata file. The file must be hosted on the component, and may be xz compressed. The file CRC can be used for file caching. The general metadata file can be read to get the locations of other metadata files (COMP_METADATA_TYPE) and translations, which may be hosted either on the vehicle or the internet. For more information see: <https://mavlink.io/en/services/component_information.html>. Note: Camera components should use CAMERA_INFORMATION instead, and autopilots may use both this message and AUTOPILOT_VERSION."]
14790#[derive(Debug, Clone, PartialEq)]
14791#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14792#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14793pub struct COMPONENT_METADATA_DATA {
14794 #[doc = "Timestamp (time since system boot)."]
14795 pub time_boot_ms: u32,
14796 #[doc = "CRC32 of the general metadata file."]
14797 pub file_crc: u32,
14798 #[doc = "MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated."]
14799 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14800 pub uri: [u8; 100],
14801}
14802impl COMPONENT_METADATA_DATA {
14803 pub const ENCODED_LEN: usize = 108usize;
14804 pub const DEFAULT: Self = Self {
14805 time_boot_ms: 0_u32,
14806 file_crc: 0_u32,
14807 uri: [0_u8; 100usize],
14808 };
14809 #[cfg(feature = "arbitrary")]
14810 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14811 use arbitrary::{Arbitrary, Unstructured};
14812 let mut buf = [0u8; 1024];
14813 rng.fill_bytes(&mut buf);
14814 let mut unstructured = Unstructured::new(&buf);
14815 Self::arbitrary(&mut unstructured).unwrap_or_default()
14816 }
14817}
14818impl Default for COMPONENT_METADATA_DATA {
14819 fn default() -> Self {
14820 Self::DEFAULT.clone()
14821 }
14822}
14823impl MessageData for COMPONENT_METADATA_DATA {
14824 type Message = MavMessage;
14825 const ID: u32 = 397u32;
14826 const NAME: &'static str = "COMPONENT_METADATA";
14827 const EXTRA_CRC: u8 = 182u8;
14828 const ENCODED_LEN: usize = 108usize;
14829 fn deser(
14830 _version: MavlinkVersion,
14831 __input: &[u8],
14832 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14833 let avail_len = __input.len();
14834 let mut payload_buf = [0; Self::ENCODED_LEN];
14835 let mut buf = if avail_len < Self::ENCODED_LEN {
14836 payload_buf[0..avail_len].copy_from_slice(__input);
14837 Bytes::new(&payload_buf)
14838 } else {
14839 Bytes::new(__input)
14840 };
14841 let mut __struct = Self::default();
14842 __struct.time_boot_ms = buf.get_u32_le();
14843 __struct.file_crc = buf.get_u32_le();
14844 for v in &mut __struct.uri {
14845 let val = buf.get_u8();
14846 *v = val;
14847 }
14848 Ok(__struct)
14849 }
14850 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14851 let mut __tmp = BytesMut::new(bytes);
14852 #[allow(clippy::absurd_extreme_comparisons)]
14853 #[allow(unused_comparisons)]
14854 if __tmp.remaining() < Self::ENCODED_LEN {
14855 panic!(
14856 "buffer is too small (need {} bytes, but got {})",
14857 Self::ENCODED_LEN,
14858 __tmp.remaining(),
14859 )
14860 }
14861 __tmp.put_u32_le(self.time_boot_ms);
14862 __tmp.put_u32_le(self.file_crc);
14863 for val in &self.uri {
14864 __tmp.put_u8(*val);
14865 }
14866 if matches!(version, MavlinkVersion::V2) {
14867 let len = __tmp.len();
14868 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14869 } else {
14870 __tmp.len()
14871 }
14872 }
14873}
14874#[doc = "id: 8"]
14875#[doc = "Status generated in each node in the communication chain and injected into MAVLink stream."]
14876#[derive(Debug, Clone, PartialEq)]
14877#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14878#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14879pub struct LINK_NODE_STATUS_DATA {
14880 #[doc = "Timestamp (time since system boot)."]
14881 pub timestamp: u64,
14882 #[doc = "Transmit rate"]
14883 pub tx_rate: u32,
14884 #[doc = "Receive rate"]
14885 pub rx_rate: u32,
14886 #[doc = "Messages sent"]
14887 pub messages_sent: u32,
14888 #[doc = "Messages received (estimated from counting seq)"]
14889 pub messages_received: u32,
14890 #[doc = "Messages lost (estimated from counting seq)"]
14891 pub messages_lost: u32,
14892 #[doc = "Number of bytes that could not be parsed correctly."]
14893 pub rx_parse_err: u16,
14894 #[doc = "Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX"]
14895 pub tx_overflows: u16,
14896 #[doc = "Receive buffer overflows. This number wraps around as it reaches UINT16_MAX"]
14897 pub rx_overflows: u16,
14898 #[doc = "Remaining free transmit buffer space"]
14899 pub tx_buf: u8,
14900 #[doc = "Remaining free receive buffer space"]
14901 pub rx_buf: u8,
14902}
14903impl LINK_NODE_STATUS_DATA {
14904 pub const ENCODED_LEN: usize = 36usize;
14905 pub const DEFAULT: Self = Self {
14906 timestamp: 0_u64,
14907 tx_rate: 0_u32,
14908 rx_rate: 0_u32,
14909 messages_sent: 0_u32,
14910 messages_received: 0_u32,
14911 messages_lost: 0_u32,
14912 rx_parse_err: 0_u16,
14913 tx_overflows: 0_u16,
14914 rx_overflows: 0_u16,
14915 tx_buf: 0_u8,
14916 rx_buf: 0_u8,
14917 };
14918 #[cfg(feature = "arbitrary")]
14919 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14920 use arbitrary::{Arbitrary, Unstructured};
14921 let mut buf = [0u8; 1024];
14922 rng.fill_bytes(&mut buf);
14923 let mut unstructured = Unstructured::new(&buf);
14924 Self::arbitrary(&mut unstructured).unwrap_or_default()
14925 }
14926}
14927impl Default for LINK_NODE_STATUS_DATA {
14928 fn default() -> Self {
14929 Self::DEFAULT.clone()
14930 }
14931}
14932impl MessageData for LINK_NODE_STATUS_DATA {
14933 type Message = MavMessage;
14934 const ID: u32 = 8u32;
14935 const NAME: &'static str = "LINK_NODE_STATUS";
14936 const EXTRA_CRC: u8 = 117u8;
14937 const ENCODED_LEN: usize = 36usize;
14938 fn deser(
14939 _version: MavlinkVersion,
14940 __input: &[u8],
14941 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14942 let avail_len = __input.len();
14943 let mut payload_buf = [0; Self::ENCODED_LEN];
14944 let mut buf = if avail_len < Self::ENCODED_LEN {
14945 payload_buf[0..avail_len].copy_from_slice(__input);
14946 Bytes::new(&payload_buf)
14947 } else {
14948 Bytes::new(__input)
14949 };
14950 let mut __struct = Self::default();
14951 __struct.timestamp = buf.get_u64_le();
14952 __struct.tx_rate = buf.get_u32_le();
14953 __struct.rx_rate = buf.get_u32_le();
14954 __struct.messages_sent = buf.get_u32_le();
14955 __struct.messages_received = buf.get_u32_le();
14956 __struct.messages_lost = buf.get_u32_le();
14957 __struct.rx_parse_err = buf.get_u16_le();
14958 __struct.tx_overflows = buf.get_u16_le();
14959 __struct.rx_overflows = buf.get_u16_le();
14960 __struct.tx_buf = buf.get_u8();
14961 __struct.rx_buf = buf.get_u8();
14962 Ok(__struct)
14963 }
14964 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14965 let mut __tmp = BytesMut::new(bytes);
14966 #[allow(clippy::absurd_extreme_comparisons)]
14967 #[allow(unused_comparisons)]
14968 if __tmp.remaining() < Self::ENCODED_LEN {
14969 panic!(
14970 "buffer is too small (need {} bytes, but got {})",
14971 Self::ENCODED_LEN,
14972 __tmp.remaining(),
14973 )
14974 }
14975 __tmp.put_u64_le(self.timestamp);
14976 __tmp.put_u32_le(self.tx_rate);
14977 __tmp.put_u32_le(self.rx_rate);
14978 __tmp.put_u32_le(self.messages_sent);
14979 __tmp.put_u32_le(self.messages_received);
14980 __tmp.put_u32_le(self.messages_lost);
14981 __tmp.put_u16_le(self.rx_parse_err);
14982 __tmp.put_u16_le(self.tx_overflows);
14983 __tmp.put_u16_le(self.rx_overflows);
14984 __tmp.put_u8(self.tx_buf);
14985 __tmp.put_u8(self.rx_buf);
14986 if matches!(version, MavlinkVersion::V2) {
14987 let len = __tmp.len();
14988 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14989 } else {
14990 __tmp.len()
14991 }
14992 }
14993}
14994#[doc = "id: 64"]
14995#[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
14996#[derive(Debug, Clone, PartialEq)]
14997#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14998#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14999pub struct LOCAL_POSITION_NED_COV_DATA {
15000 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15001 pub time_usec: u64,
15002 #[doc = "X Position"]
15003 pub x: f32,
15004 #[doc = "Y Position"]
15005 pub y: f32,
15006 #[doc = "Z Position"]
15007 pub z: f32,
15008 #[doc = "X Speed"]
15009 pub vx: f32,
15010 #[doc = "Y Speed"]
15011 pub vy: f32,
15012 #[doc = "Z Speed"]
15013 pub vz: f32,
15014 #[doc = "X Acceleration"]
15015 pub ax: f32,
15016 #[doc = "Y Acceleration"]
15017 pub ay: f32,
15018 #[doc = "Z Acceleration"]
15019 pub az: f32,
15020 #[doc = "Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
15021 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15022 pub covariance: [f32; 45],
15023 #[doc = "Class id of the estimator this estimate originated from."]
15024 pub estimator_type: MavEstimatorType,
15025}
15026impl LOCAL_POSITION_NED_COV_DATA {
15027 pub const ENCODED_LEN: usize = 225usize;
15028 pub const DEFAULT: Self = Self {
15029 time_usec: 0_u64,
15030 x: 0.0_f32,
15031 y: 0.0_f32,
15032 z: 0.0_f32,
15033 vx: 0.0_f32,
15034 vy: 0.0_f32,
15035 vz: 0.0_f32,
15036 ax: 0.0_f32,
15037 ay: 0.0_f32,
15038 az: 0.0_f32,
15039 covariance: [0.0_f32; 45usize],
15040 estimator_type: MavEstimatorType::DEFAULT,
15041 };
15042 #[cfg(feature = "arbitrary")]
15043 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15044 use arbitrary::{Arbitrary, Unstructured};
15045 let mut buf = [0u8; 1024];
15046 rng.fill_bytes(&mut buf);
15047 let mut unstructured = Unstructured::new(&buf);
15048 Self::arbitrary(&mut unstructured).unwrap_or_default()
15049 }
15050}
15051impl Default for LOCAL_POSITION_NED_COV_DATA {
15052 fn default() -> Self {
15053 Self::DEFAULT.clone()
15054 }
15055}
15056impl MessageData for LOCAL_POSITION_NED_COV_DATA {
15057 type Message = MavMessage;
15058 const ID: u32 = 64u32;
15059 const NAME: &'static str = "LOCAL_POSITION_NED_COV";
15060 const EXTRA_CRC: u8 = 191u8;
15061 const ENCODED_LEN: usize = 225usize;
15062 fn deser(
15063 _version: MavlinkVersion,
15064 __input: &[u8],
15065 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15066 let avail_len = __input.len();
15067 let mut payload_buf = [0; Self::ENCODED_LEN];
15068 let mut buf = if avail_len < Self::ENCODED_LEN {
15069 payload_buf[0..avail_len].copy_from_slice(__input);
15070 Bytes::new(&payload_buf)
15071 } else {
15072 Bytes::new(__input)
15073 };
15074 let mut __struct = Self::default();
15075 __struct.time_usec = buf.get_u64_le();
15076 __struct.x = buf.get_f32_le();
15077 __struct.y = buf.get_f32_le();
15078 __struct.z = buf.get_f32_le();
15079 __struct.vx = buf.get_f32_le();
15080 __struct.vy = buf.get_f32_le();
15081 __struct.vz = buf.get_f32_le();
15082 __struct.ax = buf.get_f32_le();
15083 __struct.ay = buf.get_f32_le();
15084 __struct.az = buf.get_f32_le();
15085 for v in &mut __struct.covariance {
15086 let val = buf.get_f32_le();
15087 *v = val;
15088 }
15089 let tmp = buf.get_u8();
15090 __struct.estimator_type =
15091 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15092 enum_type: "MavEstimatorType",
15093 value: tmp as u32,
15094 })?;
15095 Ok(__struct)
15096 }
15097 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15098 let mut __tmp = BytesMut::new(bytes);
15099 #[allow(clippy::absurd_extreme_comparisons)]
15100 #[allow(unused_comparisons)]
15101 if __tmp.remaining() < Self::ENCODED_LEN {
15102 panic!(
15103 "buffer is too small (need {} bytes, but got {})",
15104 Self::ENCODED_LEN,
15105 __tmp.remaining(),
15106 )
15107 }
15108 __tmp.put_u64_le(self.time_usec);
15109 __tmp.put_f32_le(self.x);
15110 __tmp.put_f32_le(self.y);
15111 __tmp.put_f32_le(self.z);
15112 __tmp.put_f32_le(self.vx);
15113 __tmp.put_f32_le(self.vy);
15114 __tmp.put_f32_le(self.vz);
15115 __tmp.put_f32_le(self.ax);
15116 __tmp.put_f32_le(self.ay);
15117 __tmp.put_f32_le(self.az);
15118 for val in &self.covariance {
15119 __tmp.put_f32_le(*val);
15120 }
15121 __tmp.put_u8(self.estimator_type as u8);
15122 if matches!(version, MavlinkVersion::V2) {
15123 let len = __tmp.len();
15124 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15125 } else {
15126 __tmp.len()
15127 }
15128 }
15129}
15130#[doc = "id: 387"]
15131#[doc = "A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling)."]
15132#[derive(Debug, Clone, PartialEq)]
15133#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15134#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15135pub struct CANFD_FRAME_DATA {
15136 #[doc = "Frame ID"]
15137 pub id: u32,
15138 #[doc = "System ID."]
15139 pub target_system: u8,
15140 #[doc = "Component ID."]
15141 pub target_component: u8,
15142 #[doc = "bus number"]
15143 pub bus: u8,
15144 #[doc = "Frame length"]
15145 pub len: u8,
15146 #[doc = "Frame data"]
15147 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15148 pub data: [u8; 64],
15149}
15150impl CANFD_FRAME_DATA {
15151 pub const ENCODED_LEN: usize = 72usize;
15152 pub const DEFAULT: Self = Self {
15153 id: 0_u32,
15154 target_system: 0_u8,
15155 target_component: 0_u8,
15156 bus: 0_u8,
15157 len: 0_u8,
15158 data: [0_u8; 64usize],
15159 };
15160 #[cfg(feature = "arbitrary")]
15161 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15162 use arbitrary::{Arbitrary, Unstructured};
15163 let mut buf = [0u8; 1024];
15164 rng.fill_bytes(&mut buf);
15165 let mut unstructured = Unstructured::new(&buf);
15166 Self::arbitrary(&mut unstructured).unwrap_or_default()
15167 }
15168}
15169impl Default for CANFD_FRAME_DATA {
15170 fn default() -> Self {
15171 Self::DEFAULT.clone()
15172 }
15173}
15174impl MessageData for CANFD_FRAME_DATA {
15175 type Message = MavMessage;
15176 const ID: u32 = 387u32;
15177 const NAME: &'static str = "CANFD_FRAME";
15178 const EXTRA_CRC: u8 = 4u8;
15179 const ENCODED_LEN: usize = 72usize;
15180 fn deser(
15181 _version: MavlinkVersion,
15182 __input: &[u8],
15183 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15184 let avail_len = __input.len();
15185 let mut payload_buf = [0; Self::ENCODED_LEN];
15186 let mut buf = if avail_len < Self::ENCODED_LEN {
15187 payload_buf[0..avail_len].copy_from_slice(__input);
15188 Bytes::new(&payload_buf)
15189 } else {
15190 Bytes::new(__input)
15191 };
15192 let mut __struct = Self::default();
15193 __struct.id = buf.get_u32_le();
15194 __struct.target_system = buf.get_u8();
15195 __struct.target_component = buf.get_u8();
15196 __struct.bus = buf.get_u8();
15197 __struct.len = buf.get_u8();
15198 for v in &mut __struct.data {
15199 let val = buf.get_u8();
15200 *v = val;
15201 }
15202 Ok(__struct)
15203 }
15204 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15205 let mut __tmp = BytesMut::new(bytes);
15206 #[allow(clippy::absurd_extreme_comparisons)]
15207 #[allow(unused_comparisons)]
15208 if __tmp.remaining() < Self::ENCODED_LEN {
15209 panic!(
15210 "buffer is too small (need {} bytes, but got {})",
15211 Self::ENCODED_LEN,
15212 __tmp.remaining(),
15213 )
15214 }
15215 __tmp.put_u32_le(self.id);
15216 __tmp.put_u8(self.target_system);
15217 __tmp.put_u8(self.target_component);
15218 __tmp.put_u8(self.bus);
15219 __tmp.put_u8(self.len);
15220 for val in &self.data {
15221 __tmp.put_u8(*val);
15222 }
15223 if matches!(version, MavlinkVersion::V2) {
15224 let len = __tmp.len();
15225 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15226 } else {
15227 __tmp.len()
15228 }
15229 }
15230}
15231#[doc = "id: 106"]
15232#[doc = "Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)."]
15233#[derive(Debug, Clone, PartialEq)]
15234#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15235#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15236pub struct OPTICAL_FLOW_RAD_DATA {
15237 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15238 pub time_usec: u64,
15239 #[doc = "Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the."]
15240 pub integration_time_us: u32,
15241 #[doc = "Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)"]
15242 pub integrated_x: f32,
15243 #[doc = "Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)"]
15244 pub integrated_y: f32,
15245 #[doc = "RH rotation around X axis"]
15246 pub integrated_xgyro: f32,
15247 #[doc = "RH rotation around Y axis"]
15248 pub integrated_ygyro: f32,
15249 #[doc = "RH rotation around Z axis"]
15250 pub integrated_zgyro: f32,
15251 #[doc = "Time since the distance was sampled."]
15252 pub time_delta_distance_us: u32,
15253 #[doc = "Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance."]
15254 pub distance: f32,
15255 #[doc = "Temperature"]
15256 pub temperature: i16,
15257 #[doc = "Sensor ID"]
15258 pub sensor_id: u8,
15259 #[doc = "Optical flow quality / confidence. 0: no valid flow, 255: maximum quality"]
15260 pub quality: u8,
15261}
15262impl OPTICAL_FLOW_RAD_DATA {
15263 pub const ENCODED_LEN: usize = 44usize;
15264 pub const DEFAULT: Self = Self {
15265 time_usec: 0_u64,
15266 integration_time_us: 0_u32,
15267 integrated_x: 0.0_f32,
15268 integrated_y: 0.0_f32,
15269 integrated_xgyro: 0.0_f32,
15270 integrated_ygyro: 0.0_f32,
15271 integrated_zgyro: 0.0_f32,
15272 time_delta_distance_us: 0_u32,
15273 distance: 0.0_f32,
15274 temperature: 0_i16,
15275 sensor_id: 0_u8,
15276 quality: 0_u8,
15277 };
15278 #[cfg(feature = "arbitrary")]
15279 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15280 use arbitrary::{Arbitrary, Unstructured};
15281 let mut buf = [0u8; 1024];
15282 rng.fill_bytes(&mut buf);
15283 let mut unstructured = Unstructured::new(&buf);
15284 Self::arbitrary(&mut unstructured).unwrap_or_default()
15285 }
15286}
15287impl Default for OPTICAL_FLOW_RAD_DATA {
15288 fn default() -> Self {
15289 Self::DEFAULT.clone()
15290 }
15291}
15292impl MessageData for OPTICAL_FLOW_RAD_DATA {
15293 type Message = MavMessage;
15294 const ID: u32 = 106u32;
15295 const NAME: &'static str = "OPTICAL_FLOW_RAD";
15296 const EXTRA_CRC: u8 = 138u8;
15297 const ENCODED_LEN: usize = 44usize;
15298 fn deser(
15299 _version: MavlinkVersion,
15300 __input: &[u8],
15301 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15302 let avail_len = __input.len();
15303 let mut payload_buf = [0; Self::ENCODED_LEN];
15304 let mut buf = if avail_len < Self::ENCODED_LEN {
15305 payload_buf[0..avail_len].copy_from_slice(__input);
15306 Bytes::new(&payload_buf)
15307 } else {
15308 Bytes::new(__input)
15309 };
15310 let mut __struct = Self::default();
15311 __struct.time_usec = buf.get_u64_le();
15312 __struct.integration_time_us = buf.get_u32_le();
15313 __struct.integrated_x = buf.get_f32_le();
15314 __struct.integrated_y = buf.get_f32_le();
15315 __struct.integrated_xgyro = buf.get_f32_le();
15316 __struct.integrated_ygyro = buf.get_f32_le();
15317 __struct.integrated_zgyro = buf.get_f32_le();
15318 __struct.time_delta_distance_us = buf.get_u32_le();
15319 __struct.distance = buf.get_f32_le();
15320 __struct.temperature = buf.get_i16_le();
15321 __struct.sensor_id = buf.get_u8();
15322 __struct.quality = buf.get_u8();
15323 Ok(__struct)
15324 }
15325 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15326 let mut __tmp = BytesMut::new(bytes);
15327 #[allow(clippy::absurd_extreme_comparisons)]
15328 #[allow(unused_comparisons)]
15329 if __tmp.remaining() < Self::ENCODED_LEN {
15330 panic!(
15331 "buffer is too small (need {} bytes, but got {})",
15332 Self::ENCODED_LEN,
15333 __tmp.remaining(),
15334 )
15335 }
15336 __tmp.put_u64_le(self.time_usec);
15337 __tmp.put_u32_le(self.integration_time_us);
15338 __tmp.put_f32_le(self.integrated_x);
15339 __tmp.put_f32_le(self.integrated_y);
15340 __tmp.put_f32_le(self.integrated_xgyro);
15341 __tmp.put_f32_le(self.integrated_ygyro);
15342 __tmp.put_f32_le(self.integrated_zgyro);
15343 __tmp.put_u32_le(self.time_delta_distance_us);
15344 __tmp.put_f32_le(self.distance);
15345 __tmp.put_i16_le(self.temperature);
15346 __tmp.put_u8(self.sensor_id);
15347 __tmp.put_u8(self.quality);
15348 if matches!(version, MavlinkVersion::V2) {
15349 let len = __tmp.len();
15350 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15351 } else {
15352 __tmp.len()
15353 }
15354 }
15355}
15356#[doc = "id: 258"]
15357#[doc = "Control vehicle tone generation (buzzer)."]
15358#[derive(Debug, Clone, PartialEq)]
15359#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15360#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15361pub struct PLAY_TUNE_DATA {
15362 #[doc = "System ID"]
15363 pub target_system: u8,
15364 #[doc = "Component ID"]
15365 pub target_component: u8,
15366 #[doc = "tune in board specific format"]
15367 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15368 pub tune: [u8; 30],
15369 #[doc = "tune extension (appended to tune)"]
15370 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15371 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15372 pub tune2: [u8; 200],
15373}
15374impl PLAY_TUNE_DATA {
15375 pub const ENCODED_LEN: usize = 232usize;
15376 pub const DEFAULT: Self = Self {
15377 target_system: 0_u8,
15378 target_component: 0_u8,
15379 tune: [0_u8; 30usize],
15380 tune2: [0_u8; 200usize],
15381 };
15382 #[cfg(feature = "arbitrary")]
15383 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15384 use arbitrary::{Arbitrary, Unstructured};
15385 let mut buf = [0u8; 1024];
15386 rng.fill_bytes(&mut buf);
15387 let mut unstructured = Unstructured::new(&buf);
15388 Self::arbitrary(&mut unstructured).unwrap_or_default()
15389 }
15390}
15391impl Default for PLAY_TUNE_DATA {
15392 fn default() -> Self {
15393 Self::DEFAULT.clone()
15394 }
15395}
15396impl MessageData for PLAY_TUNE_DATA {
15397 type Message = MavMessage;
15398 const ID: u32 = 258u32;
15399 const NAME: &'static str = "PLAY_TUNE";
15400 const EXTRA_CRC: u8 = 187u8;
15401 const ENCODED_LEN: usize = 232usize;
15402 fn deser(
15403 _version: MavlinkVersion,
15404 __input: &[u8],
15405 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15406 let avail_len = __input.len();
15407 let mut payload_buf = [0; Self::ENCODED_LEN];
15408 let mut buf = if avail_len < Self::ENCODED_LEN {
15409 payload_buf[0..avail_len].copy_from_slice(__input);
15410 Bytes::new(&payload_buf)
15411 } else {
15412 Bytes::new(__input)
15413 };
15414 let mut __struct = Self::default();
15415 __struct.target_system = buf.get_u8();
15416 __struct.target_component = buf.get_u8();
15417 for v in &mut __struct.tune {
15418 let val = buf.get_u8();
15419 *v = val;
15420 }
15421 for v in &mut __struct.tune2 {
15422 let val = buf.get_u8();
15423 *v = val;
15424 }
15425 Ok(__struct)
15426 }
15427 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15428 let mut __tmp = BytesMut::new(bytes);
15429 #[allow(clippy::absurd_extreme_comparisons)]
15430 #[allow(unused_comparisons)]
15431 if __tmp.remaining() < Self::ENCODED_LEN {
15432 panic!(
15433 "buffer is too small (need {} bytes, but got {})",
15434 Self::ENCODED_LEN,
15435 __tmp.remaining(),
15436 )
15437 }
15438 __tmp.put_u8(self.target_system);
15439 __tmp.put_u8(self.target_component);
15440 for val in &self.tune {
15441 __tmp.put_u8(*val);
15442 }
15443 for val in &self.tune2 {
15444 __tmp.put_u8(*val);
15445 }
15446 if matches!(version, MavlinkVersion::V2) {
15447 let len = __tmp.len();
15448 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15449 } else {
15450 __tmp.len()
15451 }
15452 }
15453}
15454#[doc = "id: 396"]
15455#[doc = "Basic component information data. Should be requested using MAV_CMD_REQUEST_MESSAGE on startup, or when required."]
15456#[derive(Debug, Clone, PartialEq)]
15457#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15458#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15459pub struct COMPONENT_INFORMATION_BASIC_DATA {
15460 #[doc = "Component capability flags"]
15461 pub capabilities: MavProtocolCapability,
15462 #[doc = "Timestamp (time since system boot)."]
15463 pub time_boot_ms: u32,
15464 #[doc = "Date of manufacture as a UNIX Epoch time (since 1.1.1970) in seconds."]
15465 pub time_manufacture_s: u32,
15466 #[doc = "Name of the component vendor. Needs to be zero terminated. The field is optional and can be empty/all zeros."]
15467 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15468 pub vendor_name: [u8; 32],
15469 #[doc = "Name of the component model. Needs to be zero terminated. The field is optional and can be empty/all zeros."]
15470 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15471 pub model_name: [u8; 32],
15472 #[doc = "Software version. The recommended format is SEMVER: 'major.minor.patch' (any format may be used). The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
15473 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15474 pub software_version: [u8; 24],
15475 #[doc = "Hardware version. The recommended format is SEMVER: 'major.minor.patch' (any format may be used). The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
15476 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15477 pub hardware_version: [u8; 24],
15478 #[doc = "Hardware serial number. The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
15479 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15480 pub serial_number: [u8; 32],
15481}
15482impl COMPONENT_INFORMATION_BASIC_DATA {
15483 pub const ENCODED_LEN: usize = 160usize;
15484 pub const DEFAULT: Self = Self {
15485 capabilities: MavProtocolCapability::DEFAULT,
15486 time_boot_ms: 0_u32,
15487 time_manufacture_s: 0_u32,
15488 vendor_name: [0_u8; 32usize],
15489 model_name: [0_u8; 32usize],
15490 software_version: [0_u8; 24usize],
15491 hardware_version: [0_u8; 24usize],
15492 serial_number: [0_u8; 32usize],
15493 };
15494 #[cfg(feature = "arbitrary")]
15495 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15496 use arbitrary::{Arbitrary, Unstructured};
15497 let mut buf = [0u8; 1024];
15498 rng.fill_bytes(&mut buf);
15499 let mut unstructured = Unstructured::new(&buf);
15500 Self::arbitrary(&mut unstructured).unwrap_or_default()
15501 }
15502}
15503impl Default for COMPONENT_INFORMATION_BASIC_DATA {
15504 fn default() -> Self {
15505 Self::DEFAULT.clone()
15506 }
15507}
15508impl MessageData for COMPONENT_INFORMATION_BASIC_DATA {
15509 type Message = MavMessage;
15510 const ID: u32 = 396u32;
15511 const NAME: &'static str = "COMPONENT_INFORMATION_BASIC";
15512 const EXTRA_CRC: u8 = 50u8;
15513 const ENCODED_LEN: usize = 160usize;
15514 fn deser(
15515 _version: MavlinkVersion,
15516 __input: &[u8],
15517 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15518 let avail_len = __input.len();
15519 let mut payload_buf = [0; Self::ENCODED_LEN];
15520 let mut buf = if avail_len < Self::ENCODED_LEN {
15521 payload_buf[0..avail_len].copy_from_slice(__input);
15522 Bytes::new(&payload_buf)
15523 } else {
15524 Bytes::new(__input)
15525 };
15526 let mut __struct = Self::default();
15527 let tmp = buf.get_u64_le();
15528 __struct.capabilities = MavProtocolCapability::from_bits(
15529 tmp & MavProtocolCapability::all().bits(),
15530 )
15531 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
15532 flag_type: "MavProtocolCapability",
15533 value: tmp as u32,
15534 })?;
15535 __struct.time_boot_ms = buf.get_u32_le();
15536 __struct.time_manufacture_s = buf.get_u32_le();
15537 for v in &mut __struct.vendor_name {
15538 let val = buf.get_u8();
15539 *v = val;
15540 }
15541 for v in &mut __struct.model_name {
15542 let val = buf.get_u8();
15543 *v = val;
15544 }
15545 for v in &mut __struct.software_version {
15546 let val = buf.get_u8();
15547 *v = val;
15548 }
15549 for v in &mut __struct.hardware_version {
15550 let val = buf.get_u8();
15551 *v = val;
15552 }
15553 for v in &mut __struct.serial_number {
15554 let val = buf.get_u8();
15555 *v = val;
15556 }
15557 Ok(__struct)
15558 }
15559 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15560 let mut __tmp = BytesMut::new(bytes);
15561 #[allow(clippy::absurd_extreme_comparisons)]
15562 #[allow(unused_comparisons)]
15563 if __tmp.remaining() < Self::ENCODED_LEN {
15564 panic!(
15565 "buffer is too small (need {} bytes, but got {})",
15566 Self::ENCODED_LEN,
15567 __tmp.remaining(),
15568 )
15569 }
15570 __tmp.put_u64_le(self.capabilities.bits());
15571 __tmp.put_u32_le(self.time_boot_ms);
15572 __tmp.put_u32_le(self.time_manufacture_s);
15573 for val in &self.vendor_name {
15574 __tmp.put_u8(*val);
15575 }
15576 for val in &self.model_name {
15577 __tmp.put_u8(*val);
15578 }
15579 for val in &self.software_version {
15580 __tmp.put_u8(*val);
15581 }
15582 for val in &self.hardware_version {
15583 __tmp.put_u8(*val);
15584 }
15585 for val in &self.serial_number {
15586 __tmp.put_u8(*val);
15587 }
15588 if matches!(version, MavlinkVersion::V2) {
15589 let len = __tmp.len();
15590 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15591 } else {
15592 __tmp.len()
15593 }
15594 }
15595}
15596#[doc = "id: 12903"]
15597#[doc = "Data for filling the OpenDroneID Self ID message. The Self ID Message is an opportunity for the operator to (optionally) declare their identity and purpose of the flight. This message can provide additional information that could reduce the threat profile of a UA (Unmanned Aircraft) flying in a particular area or manner. This message can also be used to provide optional additional clarification in an emergency/remote ID system failure situation."]
15598#[derive(Debug, Clone, PartialEq)]
15599#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15600#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15601pub struct OPEN_DRONE_ID_SELF_ID_DATA {
15602 #[doc = "System ID (0 for broadcast)."]
15603 pub target_system: u8,
15604 #[doc = "Component ID (0 for broadcast)."]
15605 pub target_component: u8,
15606 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
15607 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15608 pub id_or_mac: [u8; 20],
15609 #[doc = "Indicates the type of the description field."]
15610 pub description_type: MavOdidDescType,
15611 #[doc = "Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field."]
15612 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15613 pub description: [u8; 23],
15614}
15615impl OPEN_DRONE_ID_SELF_ID_DATA {
15616 pub const ENCODED_LEN: usize = 46usize;
15617 pub const DEFAULT: Self = Self {
15618 target_system: 0_u8,
15619 target_component: 0_u8,
15620 id_or_mac: [0_u8; 20usize],
15621 description_type: MavOdidDescType::DEFAULT,
15622 description: [0_u8; 23usize],
15623 };
15624 #[cfg(feature = "arbitrary")]
15625 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15626 use arbitrary::{Arbitrary, Unstructured};
15627 let mut buf = [0u8; 1024];
15628 rng.fill_bytes(&mut buf);
15629 let mut unstructured = Unstructured::new(&buf);
15630 Self::arbitrary(&mut unstructured).unwrap_or_default()
15631 }
15632}
15633impl Default for OPEN_DRONE_ID_SELF_ID_DATA {
15634 fn default() -> Self {
15635 Self::DEFAULT.clone()
15636 }
15637}
15638impl MessageData for OPEN_DRONE_ID_SELF_ID_DATA {
15639 type Message = MavMessage;
15640 const ID: u32 = 12903u32;
15641 const NAME: &'static str = "OPEN_DRONE_ID_SELF_ID";
15642 const EXTRA_CRC: u8 = 249u8;
15643 const ENCODED_LEN: usize = 46usize;
15644 fn deser(
15645 _version: MavlinkVersion,
15646 __input: &[u8],
15647 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15648 let avail_len = __input.len();
15649 let mut payload_buf = [0; Self::ENCODED_LEN];
15650 let mut buf = if avail_len < Self::ENCODED_LEN {
15651 payload_buf[0..avail_len].copy_from_slice(__input);
15652 Bytes::new(&payload_buf)
15653 } else {
15654 Bytes::new(__input)
15655 };
15656 let mut __struct = Self::default();
15657 __struct.target_system = buf.get_u8();
15658 __struct.target_component = buf.get_u8();
15659 for v in &mut __struct.id_or_mac {
15660 let val = buf.get_u8();
15661 *v = val;
15662 }
15663 let tmp = buf.get_u8();
15664 __struct.description_type =
15665 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15666 enum_type: "MavOdidDescType",
15667 value: tmp as u32,
15668 })?;
15669 for v in &mut __struct.description {
15670 let val = buf.get_u8();
15671 *v = val;
15672 }
15673 Ok(__struct)
15674 }
15675 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15676 let mut __tmp = BytesMut::new(bytes);
15677 #[allow(clippy::absurd_extreme_comparisons)]
15678 #[allow(unused_comparisons)]
15679 if __tmp.remaining() < Self::ENCODED_LEN {
15680 panic!(
15681 "buffer is too small (need {} bytes, but got {})",
15682 Self::ENCODED_LEN,
15683 __tmp.remaining(),
15684 )
15685 }
15686 __tmp.put_u8(self.target_system);
15687 __tmp.put_u8(self.target_component);
15688 for val in &self.id_or_mac {
15689 __tmp.put_u8(*val);
15690 }
15691 __tmp.put_u8(self.description_type as u8);
15692 for val in &self.description {
15693 __tmp.put_u8(*val);
15694 }
15695 if matches!(version, MavlinkVersion::V2) {
15696 let len = __tmp.len();
15697 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15698 } else {
15699 __tmp.len()
15700 }
15701 }
15702}
15703#[doc = "id: 0"]
15704#[doc = "The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at <https://mavlink.io/en/services/heartbeat.html>."]
15705#[derive(Debug, Clone, PartialEq)]
15706#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15707#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15708pub struct HEARTBEAT_DATA {
15709 #[doc = "A bitfield for use for autopilot-specific flags"]
15710 pub custom_mode: u32,
15711 #[doc = "Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type."]
15712 pub mavtype: MavType,
15713 #[doc = "Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers."]
15714 pub autopilot: MavAutopilot,
15715 #[doc = "System mode bitmap."]
15716 pub base_mode: MavModeFlag,
15717 #[doc = "System status flag."]
15718 pub system_status: MavState,
15719 #[doc = "MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version"]
15720 pub mavlink_version: u8,
15721}
15722impl HEARTBEAT_DATA {
15723 pub const ENCODED_LEN: usize = 9usize;
15724 pub const DEFAULT: Self = Self {
15725 custom_mode: 0_u32,
15726 mavtype: MavType::DEFAULT,
15727 autopilot: MavAutopilot::DEFAULT,
15728 base_mode: MavModeFlag::DEFAULT,
15729 system_status: MavState::DEFAULT,
15730 mavlink_version: 0_u8,
15731 };
15732 #[cfg(feature = "arbitrary")]
15733 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15734 use arbitrary::{Arbitrary, Unstructured};
15735 let mut buf = [0u8; 1024];
15736 rng.fill_bytes(&mut buf);
15737 let mut unstructured = Unstructured::new(&buf);
15738 Self::arbitrary(&mut unstructured).unwrap_or_default()
15739 }
15740}
15741impl Default for HEARTBEAT_DATA {
15742 fn default() -> Self {
15743 Self::DEFAULT.clone()
15744 }
15745}
15746impl MessageData for HEARTBEAT_DATA {
15747 type Message = MavMessage;
15748 const ID: u32 = 0u32;
15749 const NAME: &'static str = "HEARTBEAT";
15750 const EXTRA_CRC: u8 = 50u8;
15751 const ENCODED_LEN: usize = 9usize;
15752 fn deser(
15753 _version: MavlinkVersion,
15754 __input: &[u8],
15755 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15756 let avail_len = __input.len();
15757 let mut payload_buf = [0; Self::ENCODED_LEN];
15758 let mut buf = if avail_len < Self::ENCODED_LEN {
15759 payload_buf[0..avail_len].copy_from_slice(__input);
15760 Bytes::new(&payload_buf)
15761 } else {
15762 Bytes::new(__input)
15763 };
15764 let mut __struct = Self::default();
15765 __struct.custom_mode = buf.get_u32_le();
15766 let tmp = buf.get_u8();
15767 __struct.mavtype =
15768 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15769 enum_type: "MavType",
15770 value: tmp as u32,
15771 })?;
15772 let tmp = buf.get_u8();
15773 __struct.autopilot =
15774 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15775 enum_type: "MavAutopilot",
15776 value: tmp as u32,
15777 })?;
15778 let tmp = buf.get_u8();
15779 __struct.base_mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
15780 ::mavlink_core::error::ParserError::InvalidFlag {
15781 flag_type: "MavModeFlag",
15782 value: tmp as u32,
15783 },
15784 )?;
15785 let tmp = buf.get_u8();
15786 __struct.system_status =
15787 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15788 enum_type: "MavState",
15789 value: tmp as u32,
15790 })?;
15791 __struct.mavlink_version = buf.get_u8();
15792 Ok(__struct)
15793 }
15794 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15795 let mut __tmp = BytesMut::new(bytes);
15796 #[allow(clippy::absurd_extreme_comparisons)]
15797 #[allow(unused_comparisons)]
15798 if __tmp.remaining() < Self::ENCODED_LEN {
15799 panic!(
15800 "buffer is too small (need {} bytes, but got {})",
15801 Self::ENCODED_LEN,
15802 __tmp.remaining(),
15803 )
15804 }
15805 __tmp.put_u32_le(self.custom_mode);
15806 __tmp.put_u8(self.mavtype as u8);
15807 __tmp.put_u8(self.autopilot as u8);
15808 __tmp.put_u8(self.base_mode.bits());
15809 __tmp.put_u8(self.system_status as u8);
15810 __tmp.put_u8(self.mavlink_version);
15811 if matches!(version, MavlinkVersion::V2) {
15812 let len = __tmp.len();
15813 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15814 } else {
15815 __tmp.len()
15816 }
15817 }
15818}
15819#[doc = "id: 410"]
15820#[doc = "Event message. Each new event from a particular component gets a new sequence number. The same message might be sent multiple times if (re-)requested. Most events are broadcast, some can be specific to a target component (as receivers keep track of the sequence for missed events, all events need to be broadcast. Thus we use destination_component instead of target_component)."]
15821#[derive(Debug, Clone, PartialEq)]
15822#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15823#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15824pub struct EVENT_DATA {
15825 #[doc = "Event ID (as defined in the component metadata)"]
15826 pub id: u32,
15827 #[doc = "Timestamp (time since system boot when the event happened)."]
15828 pub event_time_boot_ms: u32,
15829 #[doc = "Sequence number."]
15830 pub sequence: u16,
15831 #[doc = "Component ID"]
15832 pub destination_component: u8,
15833 #[doc = "System ID"]
15834 pub destination_system: u8,
15835 #[doc = "Log levels: 4 bits MSB: internal (for logging purposes), 4 bits LSB: external. Levels: Emergency = 0, Alert = 1, Critical = 2, Error = 3, Warning = 4, Notice = 5, Info = 6, Debug = 7, Protocol = 8, Disabled = 9"]
15836 pub log_levels: u8,
15837 #[doc = "Arguments (depend on event ID)."]
15838 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15839 pub arguments: [u8; 40],
15840}
15841impl EVENT_DATA {
15842 pub const ENCODED_LEN: usize = 53usize;
15843 pub const DEFAULT: Self = Self {
15844 id: 0_u32,
15845 event_time_boot_ms: 0_u32,
15846 sequence: 0_u16,
15847 destination_component: 0_u8,
15848 destination_system: 0_u8,
15849 log_levels: 0_u8,
15850 arguments: [0_u8; 40usize],
15851 };
15852 #[cfg(feature = "arbitrary")]
15853 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15854 use arbitrary::{Arbitrary, Unstructured};
15855 let mut buf = [0u8; 1024];
15856 rng.fill_bytes(&mut buf);
15857 let mut unstructured = Unstructured::new(&buf);
15858 Self::arbitrary(&mut unstructured).unwrap_or_default()
15859 }
15860}
15861impl Default for EVENT_DATA {
15862 fn default() -> Self {
15863 Self::DEFAULT.clone()
15864 }
15865}
15866impl MessageData for EVENT_DATA {
15867 type Message = MavMessage;
15868 const ID: u32 = 410u32;
15869 const NAME: &'static str = "EVENT";
15870 const EXTRA_CRC: u8 = 160u8;
15871 const ENCODED_LEN: usize = 53usize;
15872 fn deser(
15873 _version: MavlinkVersion,
15874 __input: &[u8],
15875 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15876 let avail_len = __input.len();
15877 let mut payload_buf = [0; Self::ENCODED_LEN];
15878 let mut buf = if avail_len < Self::ENCODED_LEN {
15879 payload_buf[0..avail_len].copy_from_slice(__input);
15880 Bytes::new(&payload_buf)
15881 } else {
15882 Bytes::new(__input)
15883 };
15884 let mut __struct = Self::default();
15885 __struct.id = buf.get_u32_le();
15886 __struct.event_time_boot_ms = buf.get_u32_le();
15887 __struct.sequence = buf.get_u16_le();
15888 __struct.destination_component = buf.get_u8();
15889 __struct.destination_system = buf.get_u8();
15890 __struct.log_levels = buf.get_u8();
15891 for v in &mut __struct.arguments {
15892 let val = buf.get_u8();
15893 *v = val;
15894 }
15895 Ok(__struct)
15896 }
15897 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15898 let mut __tmp = BytesMut::new(bytes);
15899 #[allow(clippy::absurd_extreme_comparisons)]
15900 #[allow(unused_comparisons)]
15901 if __tmp.remaining() < Self::ENCODED_LEN {
15902 panic!(
15903 "buffer is too small (need {} bytes, but got {})",
15904 Self::ENCODED_LEN,
15905 __tmp.remaining(),
15906 )
15907 }
15908 __tmp.put_u32_le(self.id);
15909 __tmp.put_u32_le(self.event_time_boot_ms);
15910 __tmp.put_u16_le(self.sequence);
15911 __tmp.put_u8(self.destination_component);
15912 __tmp.put_u8(self.destination_system);
15913 __tmp.put_u8(self.log_levels);
15914 for val in &self.arguments {
15915 __tmp.put_u8(*val);
15916 }
15917 if matches!(version, MavlinkVersion::V2) {
15918 let len = __tmp.len();
15919 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15920 } else {
15921 __tmp.len()
15922 }
15923 }
15924}
15925#[doc = "id: 12905"]
15926#[doc = "Data for filling the OpenDroneID Operator ID message, which contains the CAA (Civil Aviation Authority) issued operator ID."]
15927#[derive(Debug, Clone, PartialEq)]
15928#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15929#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15930pub struct OPEN_DRONE_ID_OPERATOR_ID_DATA {
15931 #[doc = "System ID (0 for broadcast)."]
15932 pub target_system: u8,
15933 #[doc = "Component ID (0 for broadcast)."]
15934 pub target_component: u8,
15935 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
15936 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15937 pub id_or_mac: [u8; 20],
15938 #[doc = "Indicates the type of the operator_id field."]
15939 pub operator_id_type: MavOdidOperatorIdType,
15940 #[doc = "Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field."]
15941 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15942 pub operator_id: [u8; 20],
15943}
15944impl OPEN_DRONE_ID_OPERATOR_ID_DATA {
15945 pub const ENCODED_LEN: usize = 43usize;
15946 pub const DEFAULT: Self = Self {
15947 target_system: 0_u8,
15948 target_component: 0_u8,
15949 id_or_mac: [0_u8; 20usize],
15950 operator_id_type: MavOdidOperatorIdType::DEFAULT,
15951 operator_id: [0_u8; 20usize],
15952 };
15953 #[cfg(feature = "arbitrary")]
15954 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15955 use arbitrary::{Arbitrary, Unstructured};
15956 let mut buf = [0u8; 1024];
15957 rng.fill_bytes(&mut buf);
15958 let mut unstructured = Unstructured::new(&buf);
15959 Self::arbitrary(&mut unstructured).unwrap_or_default()
15960 }
15961}
15962impl Default for OPEN_DRONE_ID_OPERATOR_ID_DATA {
15963 fn default() -> Self {
15964 Self::DEFAULT.clone()
15965 }
15966}
15967impl MessageData for OPEN_DRONE_ID_OPERATOR_ID_DATA {
15968 type Message = MavMessage;
15969 const ID: u32 = 12905u32;
15970 const NAME: &'static str = "OPEN_DRONE_ID_OPERATOR_ID";
15971 const EXTRA_CRC: u8 = 49u8;
15972 const ENCODED_LEN: usize = 43usize;
15973 fn deser(
15974 _version: MavlinkVersion,
15975 __input: &[u8],
15976 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15977 let avail_len = __input.len();
15978 let mut payload_buf = [0; Self::ENCODED_LEN];
15979 let mut buf = if avail_len < Self::ENCODED_LEN {
15980 payload_buf[0..avail_len].copy_from_slice(__input);
15981 Bytes::new(&payload_buf)
15982 } else {
15983 Bytes::new(__input)
15984 };
15985 let mut __struct = Self::default();
15986 __struct.target_system = buf.get_u8();
15987 __struct.target_component = buf.get_u8();
15988 for v in &mut __struct.id_or_mac {
15989 let val = buf.get_u8();
15990 *v = val;
15991 }
15992 let tmp = buf.get_u8();
15993 __struct.operator_id_type =
15994 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15995 enum_type: "MavOdidOperatorIdType",
15996 value: tmp as u32,
15997 })?;
15998 for v in &mut __struct.operator_id {
15999 let val = buf.get_u8();
16000 *v = val;
16001 }
16002 Ok(__struct)
16003 }
16004 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16005 let mut __tmp = BytesMut::new(bytes);
16006 #[allow(clippy::absurd_extreme_comparisons)]
16007 #[allow(unused_comparisons)]
16008 if __tmp.remaining() < Self::ENCODED_LEN {
16009 panic!(
16010 "buffer is too small (need {} bytes, but got {})",
16011 Self::ENCODED_LEN,
16012 __tmp.remaining(),
16013 )
16014 }
16015 __tmp.put_u8(self.target_system);
16016 __tmp.put_u8(self.target_component);
16017 for val in &self.id_or_mac {
16018 __tmp.put_u8(*val);
16019 }
16020 __tmp.put_u8(self.operator_id_type as u8);
16021 for val in &self.operator_id {
16022 __tmp.put_u8(*val);
16023 }
16024 if matches!(version, MavlinkVersion::V2) {
16025 let len = __tmp.len();
16026 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16027 } else {
16028 __tmp.len()
16029 }
16030 }
16031}
16032#[doc = "id: 435"]
16033#[doc = "Information about a flight mode. The message can be enumerated to get information for all modes, or requested for a particular mode, using MAV_CMD_REQUEST_MESSAGE. Specify 0 in param2 to request that the message is emitted for all available modes or the specific index for just one mode. The modes must be available/settable for the current vehicle/frame type. Each mode should only be emitted once (even if it is both standard and custom). Note that the current mode should be emitted in CURRENT_MODE, and that if the mode list can change then AVAILABLE_MODES_MONITOR must be emitted on first change and subsequently streamed. See <https://mavlink.io/en/services/standard_modes.html>."]
16034#[derive(Debug, Clone, PartialEq)]
16035#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16036#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16037pub struct AVAILABLE_MODES_DATA {
16038 #[doc = "A bitfield for use for autopilot-specific flags"]
16039 pub custom_mode: u32,
16040 #[doc = "Mode properties."]
16041 pub properties: MavModeProperty,
16042 #[doc = "The total number of available modes for the current vehicle type."]
16043 pub number_modes: u8,
16044 #[doc = "The current mode index within number_modes, indexed from 1. The index is not guaranteed to be persistent, and may change between reboots or if the set of modes change."]
16045 pub mode_index: u8,
16046 #[doc = "Standard mode."]
16047 pub standard_mode: MavStandardMode,
16048 #[doc = "Name of custom mode, with null termination character. Should be omitted for standard modes."]
16049 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16050 pub mode_name: [u8; 35],
16051}
16052impl AVAILABLE_MODES_DATA {
16053 pub const ENCODED_LEN: usize = 46usize;
16054 pub const DEFAULT: Self = Self {
16055 custom_mode: 0_u32,
16056 properties: MavModeProperty::DEFAULT,
16057 number_modes: 0_u8,
16058 mode_index: 0_u8,
16059 standard_mode: MavStandardMode::DEFAULT,
16060 mode_name: [0_u8; 35usize],
16061 };
16062 #[cfg(feature = "arbitrary")]
16063 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16064 use arbitrary::{Arbitrary, Unstructured};
16065 let mut buf = [0u8; 1024];
16066 rng.fill_bytes(&mut buf);
16067 let mut unstructured = Unstructured::new(&buf);
16068 Self::arbitrary(&mut unstructured).unwrap_or_default()
16069 }
16070}
16071impl Default for AVAILABLE_MODES_DATA {
16072 fn default() -> Self {
16073 Self::DEFAULT.clone()
16074 }
16075}
16076impl MessageData for AVAILABLE_MODES_DATA {
16077 type Message = MavMessage;
16078 const ID: u32 = 435u32;
16079 const NAME: &'static str = "AVAILABLE_MODES";
16080 const EXTRA_CRC: u8 = 134u8;
16081 const ENCODED_LEN: usize = 46usize;
16082 fn deser(
16083 _version: MavlinkVersion,
16084 __input: &[u8],
16085 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16086 let avail_len = __input.len();
16087 let mut payload_buf = [0; Self::ENCODED_LEN];
16088 let mut buf = if avail_len < Self::ENCODED_LEN {
16089 payload_buf[0..avail_len].copy_from_slice(__input);
16090 Bytes::new(&payload_buf)
16091 } else {
16092 Bytes::new(__input)
16093 };
16094 let mut __struct = Self::default();
16095 __struct.custom_mode = buf.get_u32_le();
16096 let tmp = buf.get_u32_le();
16097 __struct.properties = MavModeProperty::from_bits(tmp & MavModeProperty::all().bits())
16098 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
16099 flag_type: "MavModeProperty",
16100 value: tmp as u32,
16101 })?;
16102 __struct.number_modes = buf.get_u8();
16103 __struct.mode_index = buf.get_u8();
16104 let tmp = buf.get_u8();
16105 __struct.standard_mode =
16106 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16107 enum_type: "MavStandardMode",
16108 value: tmp as u32,
16109 })?;
16110 for v in &mut __struct.mode_name {
16111 let val = buf.get_u8();
16112 *v = val;
16113 }
16114 Ok(__struct)
16115 }
16116 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16117 let mut __tmp = BytesMut::new(bytes);
16118 #[allow(clippy::absurd_extreme_comparisons)]
16119 #[allow(unused_comparisons)]
16120 if __tmp.remaining() < Self::ENCODED_LEN {
16121 panic!(
16122 "buffer is too small (need {} bytes, but got {})",
16123 Self::ENCODED_LEN,
16124 __tmp.remaining(),
16125 )
16126 }
16127 __tmp.put_u32_le(self.custom_mode);
16128 __tmp.put_u32_le(self.properties.bits());
16129 __tmp.put_u8(self.number_modes);
16130 __tmp.put_u8(self.mode_index);
16131 __tmp.put_u8(self.standard_mode as u8);
16132 for val in &self.mode_name {
16133 __tmp.put_u8(*val);
16134 }
16135 if matches!(version, MavlinkVersion::V2) {
16136 let len = __tmp.len();
16137 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16138 } else {
16139 __tmp.len()
16140 }
16141 }
16142}
16143#[doc = "id: 243"]
16144#[doc = "Sets the home position. \tThe home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this message). The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)."]
16145#[derive(Debug, Clone, PartialEq)]
16146#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16147#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16148pub struct SET_HOME_POSITION_DATA {
16149 #[doc = "Latitude (WGS84)"]
16150 pub latitude: i32,
16151 #[doc = "Longitude (WGS84)"]
16152 pub longitude: i32,
16153 #[doc = "Altitude (MSL). Positive for up."]
16154 pub altitude: i32,
16155 #[doc = "Local X position of this position in the local coordinate frame (NED)"]
16156 pub x: f32,
16157 #[doc = "Local Y position of this position in the local coordinate frame (NED)"]
16158 pub y: f32,
16159 #[doc = "Local Z position of this position in the local coordinate frame (NED: positive \"down\")"]
16160 pub z: f32,
16161 #[doc = "World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground"]
16162 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16163 pub q: [f32; 4],
16164 #[doc = "Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
16165 pub approach_x: f32,
16166 #[doc = "Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
16167 pub approach_y: f32,
16168 #[doc = "Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
16169 pub approach_z: f32,
16170 #[doc = "System ID."]
16171 pub target_system: u8,
16172 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16173 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16174 pub time_usec: u64,
16175}
16176impl SET_HOME_POSITION_DATA {
16177 pub const ENCODED_LEN: usize = 61usize;
16178 pub const DEFAULT: Self = Self {
16179 latitude: 0_i32,
16180 longitude: 0_i32,
16181 altitude: 0_i32,
16182 x: 0.0_f32,
16183 y: 0.0_f32,
16184 z: 0.0_f32,
16185 q: [0.0_f32; 4usize],
16186 approach_x: 0.0_f32,
16187 approach_y: 0.0_f32,
16188 approach_z: 0.0_f32,
16189 target_system: 0_u8,
16190 time_usec: 0_u64,
16191 };
16192 #[cfg(feature = "arbitrary")]
16193 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16194 use arbitrary::{Arbitrary, Unstructured};
16195 let mut buf = [0u8; 1024];
16196 rng.fill_bytes(&mut buf);
16197 let mut unstructured = Unstructured::new(&buf);
16198 Self::arbitrary(&mut unstructured).unwrap_or_default()
16199 }
16200}
16201impl Default for SET_HOME_POSITION_DATA {
16202 fn default() -> Self {
16203 Self::DEFAULT.clone()
16204 }
16205}
16206impl MessageData for SET_HOME_POSITION_DATA {
16207 type Message = MavMessage;
16208 const ID: u32 = 243u32;
16209 const NAME: &'static str = "SET_HOME_POSITION";
16210 const EXTRA_CRC: u8 = 85u8;
16211 const ENCODED_LEN: usize = 61usize;
16212 fn deser(
16213 _version: MavlinkVersion,
16214 __input: &[u8],
16215 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16216 let avail_len = __input.len();
16217 let mut payload_buf = [0; Self::ENCODED_LEN];
16218 let mut buf = if avail_len < Self::ENCODED_LEN {
16219 payload_buf[0..avail_len].copy_from_slice(__input);
16220 Bytes::new(&payload_buf)
16221 } else {
16222 Bytes::new(__input)
16223 };
16224 let mut __struct = Self::default();
16225 __struct.latitude = buf.get_i32_le();
16226 __struct.longitude = buf.get_i32_le();
16227 __struct.altitude = buf.get_i32_le();
16228 __struct.x = buf.get_f32_le();
16229 __struct.y = buf.get_f32_le();
16230 __struct.z = buf.get_f32_le();
16231 for v in &mut __struct.q {
16232 let val = buf.get_f32_le();
16233 *v = val;
16234 }
16235 __struct.approach_x = buf.get_f32_le();
16236 __struct.approach_y = buf.get_f32_le();
16237 __struct.approach_z = buf.get_f32_le();
16238 __struct.target_system = buf.get_u8();
16239 __struct.time_usec = buf.get_u64_le();
16240 Ok(__struct)
16241 }
16242 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16243 let mut __tmp = BytesMut::new(bytes);
16244 #[allow(clippy::absurd_extreme_comparisons)]
16245 #[allow(unused_comparisons)]
16246 if __tmp.remaining() < Self::ENCODED_LEN {
16247 panic!(
16248 "buffer is too small (need {} bytes, but got {})",
16249 Self::ENCODED_LEN,
16250 __tmp.remaining(),
16251 )
16252 }
16253 __tmp.put_i32_le(self.latitude);
16254 __tmp.put_i32_le(self.longitude);
16255 __tmp.put_i32_le(self.altitude);
16256 __tmp.put_f32_le(self.x);
16257 __tmp.put_f32_le(self.y);
16258 __tmp.put_f32_le(self.z);
16259 for val in &self.q {
16260 __tmp.put_f32_le(*val);
16261 }
16262 __tmp.put_f32_le(self.approach_x);
16263 __tmp.put_f32_le(self.approach_y);
16264 __tmp.put_f32_le(self.approach_z);
16265 __tmp.put_u8(self.target_system);
16266 __tmp.put_u64_le(self.time_usec);
16267 if matches!(version, MavlinkVersion::V2) {
16268 let len = __tmp.len();
16269 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16270 } else {
16271 __tmp.len()
16272 }
16273 }
16274}
16275#[doc = "id: 371"]
16276#[doc = "Fuel status. This message provides \"generic\" fuel level information for in a GCS and for triggering failsafes in an autopilot. The fuel type and associated units for fields in this message are defined in the enum MAV_FUEL_TYPE. The reported `consumed_fuel` and `remaining_fuel` must only be supplied if measured: they must not be inferred from the `maximum_fuel` and the other value. A recipient can assume that if these fields are supplied they are accurate. If not provided, the recipient can infer `remaining_fuel` from `maximum_fuel` and `consumed_fuel` on the assumption that the fuel was initially at its maximum (this is what battery monitors assume). Note however that this is an assumption, and the UI should prompt the user appropriately (i.e. notify user that they should fill the tank before boot). This kind of information may also be sent in fuel-specific messages such as BATTERY_STATUS_V2. If both messages are sent for the same fuel system, the ids and corresponding information must match. This should be streamed (nominally at 0.1 Hz)."]
16277#[derive(Debug, Clone, PartialEq)]
16278#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16279#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16280pub struct FUEL_STATUS_DATA {
16281 #[doc = "Capacity when full. Must be provided."]
16282 pub maximum_fuel: f32,
16283 #[doc = "Consumed fuel (measured). This value should not be inferred: if not measured set to NaN. NaN: field not provided."]
16284 pub consumed_fuel: f32,
16285 #[doc = "Remaining fuel until empty (measured). The value should not be inferred: if not measured set to NaN. NaN: field not provided."]
16286 pub remaining_fuel: f32,
16287 #[doc = "Positive value when emptying/using, and negative if filling/replacing. NaN: field not provided."]
16288 pub flow_rate: f32,
16289 #[doc = "Fuel temperature. NaN: field not provided."]
16290 pub temperature: f32,
16291 #[doc = "Fuel type. Defines units for fuel capacity and consumption fields above."]
16292 pub fuel_type: MavFuelType,
16293 #[doc = "Fuel ID. Must match ID of other messages for same fuel system, such as BATTERY_STATUS_V2."]
16294 pub id: u8,
16295 #[doc = "Percentage of remaining fuel, relative to full. Values: [0-100], UINT8_MAX: field not provided."]
16296 pub percent_remaining: u8,
16297}
16298impl FUEL_STATUS_DATA {
16299 pub const ENCODED_LEN: usize = 26usize;
16300 pub const DEFAULT: Self = Self {
16301 maximum_fuel: 0.0_f32,
16302 consumed_fuel: 0.0_f32,
16303 remaining_fuel: 0.0_f32,
16304 flow_rate: 0.0_f32,
16305 temperature: 0.0_f32,
16306 fuel_type: MavFuelType::DEFAULT,
16307 id: 0_u8,
16308 percent_remaining: 0_u8,
16309 };
16310 #[cfg(feature = "arbitrary")]
16311 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16312 use arbitrary::{Arbitrary, Unstructured};
16313 let mut buf = [0u8; 1024];
16314 rng.fill_bytes(&mut buf);
16315 let mut unstructured = Unstructured::new(&buf);
16316 Self::arbitrary(&mut unstructured).unwrap_or_default()
16317 }
16318}
16319impl Default for FUEL_STATUS_DATA {
16320 fn default() -> Self {
16321 Self::DEFAULT.clone()
16322 }
16323}
16324impl MessageData for FUEL_STATUS_DATA {
16325 type Message = MavMessage;
16326 const ID: u32 = 371u32;
16327 const NAME: &'static str = "FUEL_STATUS";
16328 const EXTRA_CRC: u8 = 10u8;
16329 const ENCODED_LEN: usize = 26usize;
16330 fn deser(
16331 _version: MavlinkVersion,
16332 __input: &[u8],
16333 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16334 let avail_len = __input.len();
16335 let mut payload_buf = [0; Self::ENCODED_LEN];
16336 let mut buf = if avail_len < Self::ENCODED_LEN {
16337 payload_buf[0..avail_len].copy_from_slice(__input);
16338 Bytes::new(&payload_buf)
16339 } else {
16340 Bytes::new(__input)
16341 };
16342 let mut __struct = Self::default();
16343 __struct.maximum_fuel = buf.get_f32_le();
16344 __struct.consumed_fuel = buf.get_f32_le();
16345 __struct.remaining_fuel = buf.get_f32_le();
16346 __struct.flow_rate = buf.get_f32_le();
16347 __struct.temperature = buf.get_f32_le();
16348 let tmp = buf.get_u32_le();
16349 __struct.fuel_type = FromPrimitive::from_u32(tmp).ok_or(
16350 ::mavlink_core::error::ParserError::InvalidEnum {
16351 enum_type: "MavFuelType",
16352 value: tmp as u32,
16353 },
16354 )?;
16355 __struct.id = buf.get_u8();
16356 __struct.percent_remaining = buf.get_u8();
16357 Ok(__struct)
16358 }
16359 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16360 let mut __tmp = BytesMut::new(bytes);
16361 #[allow(clippy::absurd_extreme_comparisons)]
16362 #[allow(unused_comparisons)]
16363 if __tmp.remaining() < Self::ENCODED_LEN {
16364 panic!(
16365 "buffer is too small (need {} bytes, but got {})",
16366 Self::ENCODED_LEN,
16367 __tmp.remaining(),
16368 )
16369 }
16370 __tmp.put_f32_le(self.maximum_fuel);
16371 __tmp.put_f32_le(self.consumed_fuel);
16372 __tmp.put_f32_le(self.remaining_fuel);
16373 __tmp.put_f32_le(self.flow_rate);
16374 __tmp.put_f32_le(self.temperature);
16375 __tmp.put_u32_le(self.fuel_type as u32);
16376 __tmp.put_u8(self.id);
16377 __tmp.put_u8(self.percent_remaining);
16378 if matches!(version, MavlinkVersion::V2) {
16379 let len = __tmp.len();
16380 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16381 } else {
16382 __tmp.len()
16383 }
16384 }
16385}
16386#[doc = "id: 12915"]
16387#[doc = "An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above message descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking or on WiFi Beacon."]
16388#[derive(Debug, Clone, PartialEq)]
16389#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16390#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16391pub struct OPEN_DRONE_ID_MESSAGE_PACK_DATA {
16392 #[doc = "System ID (0 for broadcast)."]
16393 pub target_system: u8,
16394 #[doc = "Component ID (0 for broadcast)."]
16395 pub target_component: u8,
16396 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
16397 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16398 pub id_or_mac: [u8; 20],
16399 #[doc = "This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length."]
16400 pub single_message_size: u8,
16401 #[doc = "Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9."]
16402 pub msg_pack_size: u8,
16403 #[doc = "Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field."]
16404 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16405 pub messages: [u8; 225],
16406}
16407impl OPEN_DRONE_ID_MESSAGE_PACK_DATA {
16408 pub const ENCODED_LEN: usize = 249usize;
16409 pub const DEFAULT: Self = Self {
16410 target_system: 0_u8,
16411 target_component: 0_u8,
16412 id_or_mac: [0_u8; 20usize],
16413 single_message_size: 0_u8,
16414 msg_pack_size: 0_u8,
16415 messages: [0_u8; 225usize],
16416 };
16417 #[cfg(feature = "arbitrary")]
16418 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16419 use arbitrary::{Arbitrary, Unstructured};
16420 let mut buf = [0u8; 1024];
16421 rng.fill_bytes(&mut buf);
16422 let mut unstructured = Unstructured::new(&buf);
16423 Self::arbitrary(&mut unstructured).unwrap_or_default()
16424 }
16425}
16426impl Default for OPEN_DRONE_ID_MESSAGE_PACK_DATA {
16427 fn default() -> Self {
16428 Self::DEFAULT.clone()
16429 }
16430}
16431impl MessageData for OPEN_DRONE_ID_MESSAGE_PACK_DATA {
16432 type Message = MavMessage;
16433 const ID: u32 = 12915u32;
16434 const NAME: &'static str = "OPEN_DRONE_ID_MESSAGE_PACK";
16435 const EXTRA_CRC: u8 = 94u8;
16436 const ENCODED_LEN: usize = 249usize;
16437 fn deser(
16438 _version: MavlinkVersion,
16439 __input: &[u8],
16440 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16441 let avail_len = __input.len();
16442 let mut payload_buf = [0; Self::ENCODED_LEN];
16443 let mut buf = if avail_len < Self::ENCODED_LEN {
16444 payload_buf[0..avail_len].copy_from_slice(__input);
16445 Bytes::new(&payload_buf)
16446 } else {
16447 Bytes::new(__input)
16448 };
16449 let mut __struct = Self::default();
16450 __struct.target_system = buf.get_u8();
16451 __struct.target_component = buf.get_u8();
16452 for v in &mut __struct.id_or_mac {
16453 let val = buf.get_u8();
16454 *v = val;
16455 }
16456 __struct.single_message_size = buf.get_u8();
16457 __struct.msg_pack_size = buf.get_u8();
16458 for v in &mut __struct.messages {
16459 let val = buf.get_u8();
16460 *v = val;
16461 }
16462 Ok(__struct)
16463 }
16464 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16465 let mut __tmp = BytesMut::new(bytes);
16466 #[allow(clippy::absurd_extreme_comparisons)]
16467 #[allow(unused_comparisons)]
16468 if __tmp.remaining() < Self::ENCODED_LEN {
16469 panic!(
16470 "buffer is too small (need {} bytes, but got {})",
16471 Self::ENCODED_LEN,
16472 __tmp.remaining(),
16473 )
16474 }
16475 __tmp.put_u8(self.target_system);
16476 __tmp.put_u8(self.target_component);
16477 for val in &self.id_or_mac {
16478 __tmp.put_u8(*val);
16479 }
16480 __tmp.put_u8(self.single_message_size);
16481 __tmp.put_u8(self.msg_pack_size);
16482 for val in &self.messages {
16483 __tmp.put_u8(*val);
16484 }
16485 if matches!(version, MavlinkVersion::V2) {
16486 let len = __tmp.len();
16487 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16488 } else {
16489 __tmp.len()
16490 }
16491 }
16492}
16493#[doc = "id: 76"]
16494#[doc = "Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands that include positional information; it offers higher precision and allows the MAV_FRAME to be specified (which may otherwise be ambiguous, particularly for altitude). The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
16495#[derive(Debug, Clone, PartialEq)]
16496#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16497#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16498pub struct COMMAND_LONG_DATA {
16499 #[doc = "Parameter 1 (for the specific command)."]
16500 pub param1: f32,
16501 #[doc = "Parameter 2 (for the specific command)."]
16502 pub param2: f32,
16503 #[doc = "Parameter 3 (for the specific command)."]
16504 pub param3: f32,
16505 #[doc = "Parameter 4 (for the specific command)."]
16506 pub param4: f32,
16507 #[doc = "Parameter 5 (for the specific command)."]
16508 pub param5: f32,
16509 #[doc = "Parameter 6 (for the specific command)."]
16510 pub param6: f32,
16511 #[doc = "Parameter 7 (for the specific command)."]
16512 pub param7: f32,
16513 #[doc = "Command ID (of command to send)."]
16514 pub command: MavCmd,
16515 #[doc = "System which should execute the command"]
16516 pub target_system: u8,
16517 #[doc = "Component which should execute the command, 0 for all components"]
16518 pub target_component: u8,
16519 #[doc = "0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)"]
16520 pub confirmation: u8,
16521}
16522impl COMMAND_LONG_DATA {
16523 pub const ENCODED_LEN: usize = 33usize;
16524 pub const DEFAULT: Self = Self {
16525 param1: 0.0_f32,
16526 param2: 0.0_f32,
16527 param3: 0.0_f32,
16528 param4: 0.0_f32,
16529 param5: 0.0_f32,
16530 param6: 0.0_f32,
16531 param7: 0.0_f32,
16532 command: MavCmd::DEFAULT,
16533 target_system: 0_u8,
16534 target_component: 0_u8,
16535 confirmation: 0_u8,
16536 };
16537 #[cfg(feature = "arbitrary")]
16538 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16539 use arbitrary::{Arbitrary, Unstructured};
16540 let mut buf = [0u8; 1024];
16541 rng.fill_bytes(&mut buf);
16542 let mut unstructured = Unstructured::new(&buf);
16543 Self::arbitrary(&mut unstructured).unwrap_or_default()
16544 }
16545}
16546impl Default for COMMAND_LONG_DATA {
16547 fn default() -> Self {
16548 Self::DEFAULT.clone()
16549 }
16550}
16551impl MessageData for COMMAND_LONG_DATA {
16552 type Message = MavMessage;
16553 const ID: u32 = 76u32;
16554 const NAME: &'static str = "COMMAND_LONG";
16555 const EXTRA_CRC: u8 = 152u8;
16556 const ENCODED_LEN: usize = 33usize;
16557 fn deser(
16558 _version: MavlinkVersion,
16559 __input: &[u8],
16560 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16561 let avail_len = __input.len();
16562 let mut payload_buf = [0; Self::ENCODED_LEN];
16563 let mut buf = if avail_len < Self::ENCODED_LEN {
16564 payload_buf[0..avail_len].copy_from_slice(__input);
16565 Bytes::new(&payload_buf)
16566 } else {
16567 Bytes::new(__input)
16568 };
16569 let mut __struct = Self::default();
16570 __struct.param1 = buf.get_f32_le();
16571 __struct.param2 = buf.get_f32_le();
16572 __struct.param3 = buf.get_f32_le();
16573 __struct.param4 = buf.get_f32_le();
16574 __struct.param5 = buf.get_f32_le();
16575 __struct.param6 = buf.get_f32_le();
16576 __struct.param7 = buf.get_f32_le();
16577 let tmp = buf.get_u16_le();
16578 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
16579 ::mavlink_core::error::ParserError::InvalidEnum {
16580 enum_type: "MavCmd",
16581 value: tmp as u32,
16582 },
16583 )?;
16584 __struct.target_system = buf.get_u8();
16585 __struct.target_component = buf.get_u8();
16586 __struct.confirmation = buf.get_u8();
16587 Ok(__struct)
16588 }
16589 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16590 let mut __tmp = BytesMut::new(bytes);
16591 #[allow(clippy::absurd_extreme_comparisons)]
16592 #[allow(unused_comparisons)]
16593 if __tmp.remaining() < Self::ENCODED_LEN {
16594 panic!(
16595 "buffer is too small (need {} bytes, but got {})",
16596 Self::ENCODED_LEN,
16597 __tmp.remaining(),
16598 )
16599 }
16600 __tmp.put_f32_le(self.param1);
16601 __tmp.put_f32_le(self.param2);
16602 __tmp.put_f32_le(self.param3);
16603 __tmp.put_f32_le(self.param4);
16604 __tmp.put_f32_le(self.param5);
16605 __tmp.put_f32_le(self.param6);
16606 __tmp.put_f32_le(self.param7);
16607 __tmp.put_u16_le(self.command as u16);
16608 __tmp.put_u8(self.target_system);
16609 __tmp.put_u8(self.target_component);
16610 __tmp.put_u8(self.confirmation);
16611 if matches!(version, MavlinkVersion::V2) {
16612 let len = __tmp.len();
16613 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16614 } else {
16615 __tmp.len()
16616 }
16617 }
16618}
16619#[doc = "id: 127"]
16620#[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
16621#[derive(Debug, Clone, PartialEq)]
16622#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16623#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16624pub struct GPS_RTK_DATA {
16625 #[doc = "Time since boot of last baseline message received."]
16626 pub time_last_baseline_ms: u32,
16627 #[doc = "GPS Time of Week of last baseline"]
16628 pub tow: u32,
16629 #[doc = "Current baseline in ECEF x or NED north component."]
16630 pub baseline_a_mm: i32,
16631 #[doc = "Current baseline in ECEF y or NED east component."]
16632 pub baseline_b_mm: i32,
16633 #[doc = "Current baseline in ECEF z or NED down component."]
16634 pub baseline_c_mm: i32,
16635 #[doc = "Current estimate of baseline accuracy."]
16636 pub accuracy: u32,
16637 #[doc = "Current number of integer ambiguity hypotheses."]
16638 pub iar_num_hypotheses: i32,
16639 #[doc = "GPS Week Number of last baseline"]
16640 pub wn: u16,
16641 #[doc = "Identification of connected RTK receiver."]
16642 pub rtk_receiver_id: u8,
16643 #[doc = "GPS-specific health report for RTK data."]
16644 pub rtk_health: u8,
16645 #[doc = "Rate of baseline messages being received by GPS"]
16646 pub rtk_rate: u8,
16647 #[doc = "Current number of sats used for RTK calculation."]
16648 pub nsats: u8,
16649 #[doc = "Coordinate system of baseline"]
16650 pub baseline_coords_type: RtkBaselineCoordinateSystem,
16651}
16652impl GPS_RTK_DATA {
16653 pub const ENCODED_LEN: usize = 35usize;
16654 pub const DEFAULT: Self = Self {
16655 time_last_baseline_ms: 0_u32,
16656 tow: 0_u32,
16657 baseline_a_mm: 0_i32,
16658 baseline_b_mm: 0_i32,
16659 baseline_c_mm: 0_i32,
16660 accuracy: 0_u32,
16661 iar_num_hypotheses: 0_i32,
16662 wn: 0_u16,
16663 rtk_receiver_id: 0_u8,
16664 rtk_health: 0_u8,
16665 rtk_rate: 0_u8,
16666 nsats: 0_u8,
16667 baseline_coords_type: RtkBaselineCoordinateSystem::DEFAULT,
16668 };
16669 #[cfg(feature = "arbitrary")]
16670 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16671 use arbitrary::{Arbitrary, Unstructured};
16672 let mut buf = [0u8; 1024];
16673 rng.fill_bytes(&mut buf);
16674 let mut unstructured = Unstructured::new(&buf);
16675 Self::arbitrary(&mut unstructured).unwrap_or_default()
16676 }
16677}
16678impl Default for GPS_RTK_DATA {
16679 fn default() -> Self {
16680 Self::DEFAULT.clone()
16681 }
16682}
16683impl MessageData for GPS_RTK_DATA {
16684 type Message = MavMessage;
16685 const ID: u32 = 127u32;
16686 const NAME: &'static str = "GPS_RTK";
16687 const EXTRA_CRC: u8 = 25u8;
16688 const ENCODED_LEN: usize = 35usize;
16689 fn deser(
16690 _version: MavlinkVersion,
16691 __input: &[u8],
16692 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16693 let avail_len = __input.len();
16694 let mut payload_buf = [0; Self::ENCODED_LEN];
16695 let mut buf = if avail_len < Self::ENCODED_LEN {
16696 payload_buf[0..avail_len].copy_from_slice(__input);
16697 Bytes::new(&payload_buf)
16698 } else {
16699 Bytes::new(__input)
16700 };
16701 let mut __struct = Self::default();
16702 __struct.time_last_baseline_ms = buf.get_u32_le();
16703 __struct.tow = buf.get_u32_le();
16704 __struct.baseline_a_mm = buf.get_i32_le();
16705 __struct.baseline_b_mm = buf.get_i32_le();
16706 __struct.baseline_c_mm = buf.get_i32_le();
16707 __struct.accuracy = buf.get_u32_le();
16708 __struct.iar_num_hypotheses = buf.get_i32_le();
16709 __struct.wn = buf.get_u16_le();
16710 __struct.rtk_receiver_id = buf.get_u8();
16711 __struct.rtk_health = buf.get_u8();
16712 __struct.rtk_rate = buf.get_u8();
16713 __struct.nsats = buf.get_u8();
16714 let tmp = buf.get_u8();
16715 __struct.baseline_coords_type =
16716 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16717 enum_type: "RtkBaselineCoordinateSystem",
16718 value: tmp as u32,
16719 })?;
16720 Ok(__struct)
16721 }
16722 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16723 let mut __tmp = BytesMut::new(bytes);
16724 #[allow(clippy::absurd_extreme_comparisons)]
16725 #[allow(unused_comparisons)]
16726 if __tmp.remaining() < Self::ENCODED_LEN {
16727 panic!(
16728 "buffer is too small (need {} bytes, but got {})",
16729 Self::ENCODED_LEN,
16730 __tmp.remaining(),
16731 )
16732 }
16733 __tmp.put_u32_le(self.time_last_baseline_ms);
16734 __tmp.put_u32_le(self.tow);
16735 __tmp.put_i32_le(self.baseline_a_mm);
16736 __tmp.put_i32_le(self.baseline_b_mm);
16737 __tmp.put_i32_le(self.baseline_c_mm);
16738 __tmp.put_u32_le(self.accuracy);
16739 __tmp.put_i32_le(self.iar_num_hypotheses);
16740 __tmp.put_u16_le(self.wn);
16741 __tmp.put_u8(self.rtk_receiver_id);
16742 __tmp.put_u8(self.rtk_health);
16743 __tmp.put_u8(self.rtk_rate);
16744 __tmp.put_u8(self.nsats);
16745 __tmp.put_u8(self.baseline_coords_type as u8);
16746 if matches!(version, MavlinkVersion::V2) {
16747 let len = __tmp.len();
16748 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16749 } else {
16750 __tmp.len()
16751 }
16752 }
16753}
16754#[doc = "id: 10003"]
16755#[doc = "Transceiver heartbeat with health report (updated every 10s)."]
16756#[derive(Debug, Clone, PartialEq)]
16757#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16758#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16759pub struct UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA {
16760 #[doc = "ADS-B transponder messages"]
16761 pub rfHealth: UavionixAdsbRfHealth,
16762}
16763impl UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA {
16764 pub const ENCODED_LEN: usize = 1usize;
16765 pub const DEFAULT: Self = Self {
16766 rfHealth: UavionixAdsbRfHealth::DEFAULT,
16767 };
16768 #[cfg(feature = "arbitrary")]
16769 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16770 use arbitrary::{Arbitrary, Unstructured};
16771 let mut buf = [0u8; 1024];
16772 rng.fill_bytes(&mut buf);
16773 let mut unstructured = Unstructured::new(&buf);
16774 Self::arbitrary(&mut unstructured).unwrap_or_default()
16775 }
16776}
16777impl Default for UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA {
16778 fn default() -> Self {
16779 Self::DEFAULT.clone()
16780 }
16781}
16782impl MessageData for UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA {
16783 type Message = MavMessage;
16784 const ID: u32 = 10003u32;
16785 const NAME: &'static str = "UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT";
16786 const EXTRA_CRC: u8 = 4u8;
16787 const ENCODED_LEN: usize = 1usize;
16788 fn deser(
16789 _version: MavlinkVersion,
16790 __input: &[u8],
16791 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16792 let avail_len = __input.len();
16793 let mut payload_buf = [0; Self::ENCODED_LEN];
16794 let mut buf = if avail_len < Self::ENCODED_LEN {
16795 payload_buf[0..avail_len].copy_from_slice(__input);
16796 Bytes::new(&payload_buf)
16797 } else {
16798 Bytes::new(__input)
16799 };
16800 let mut __struct = Self::default();
16801 let tmp = buf.get_u8();
16802 __struct.rfHealth = UavionixAdsbRfHealth::from_bits(
16803 tmp & UavionixAdsbRfHealth::all().bits(),
16804 )
16805 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
16806 flag_type: "UavionixAdsbRfHealth",
16807 value: tmp as u32,
16808 })?;
16809 Ok(__struct)
16810 }
16811 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16812 let mut __tmp = BytesMut::new(bytes);
16813 #[allow(clippy::absurd_extreme_comparisons)]
16814 #[allow(unused_comparisons)]
16815 if __tmp.remaining() < Self::ENCODED_LEN {
16816 panic!(
16817 "buffer is too small (need {} bytes, but got {})",
16818 Self::ENCODED_LEN,
16819 __tmp.remaining(),
16820 )
16821 }
16822 __tmp.put_u8(self.rfHealth.bits());
16823 if matches!(version, MavlinkVersion::V2) {
16824 let len = __tmp.len();
16825 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16826 } else {
16827 __tmp.len()
16828 }
16829 }
16830}
16831#[doc = "id: 388"]
16832#[doc = "Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages."]
16833#[derive(Debug, Clone, PartialEq)]
16834#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16835#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16836pub struct CAN_FILTER_MODIFY_DATA {
16837 #[doc = "filter IDs, length num_ids"]
16838 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16839 pub ids: [u16; 16],
16840 #[doc = "System ID."]
16841 pub target_system: u8,
16842 #[doc = "Component ID."]
16843 pub target_component: u8,
16844 #[doc = "bus number"]
16845 pub bus: u8,
16846 #[doc = "what operation to perform on the filter list. See CAN_FILTER_OP enum."]
16847 pub operation: CanFilterOp,
16848 #[doc = "number of IDs in filter list"]
16849 pub num_ids: u8,
16850}
16851impl CAN_FILTER_MODIFY_DATA {
16852 pub const ENCODED_LEN: usize = 37usize;
16853 pub const DEFAULT: Self = Self {
16854 ids: [0_u16; 16usize],
16855 target_system: 0_u8,
16856 target_component: 0_u8,
16857 bus: 0_u8,
16858 operation: CanFilterOp::DEFAULT,
16859 num_ids: 0_u8,
16860 };
16861 #[cfg(feature = "arbitrary")]
16862 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16863 use arbitrary::{Arbitrary, Unstructured};
16864 let mut buf = [0u8; 1024];
16865 rng.fill_bytes(&mut buf);
16866 let mut unstructured = Unstructured::new(&buf);
16867 Self::arbitrary(&mut unstructured).unwrap_or_default()
16868 }
16869}
16870impl Default for CAN_FILTER_MODIFY_DATA {
16871 fn default() -> Self {
16872 Self::DEFAULT.clone()
16873 }
16874}
16875impl MessageData for CAN_FILTER_MODIFY_DATA {
16876 type Message = MavMessage;
16877 const ID: u32 = 388u32;
16878 const NAME: &'static str = "CAN_FILTER_MODIFY";
16879 const EXTRA_CRC: u8 = 8u8;
16880 const ENCODED_LEN: usize = 37usize;
16881 fn deser(
16882 _version: MavlinkVersion,
16883 __input: &[u8],
16884 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16885 let avail_len = __input.len();
16886 let mut payload_buf = [0; Self::ENCODED_LEN];
16887 let mut buf = if avail_len < Self::ENCODED_LEN {
16888 payload_buf[0..avail_len].copy_from_slice(__input);
16889 Bytes::new(&payload_buf)
16890 } else {
16891 Bytes::new(__input)
16892 };
16893 let mut __struct = Self::default();
16894 for v in &mut __struct.ids {
16895 let val = buf.get_u16_le();
16896 *v = val;
16897 }
16898 __struct.target_system = buf.get_u8();
16899 __struct.target_component = buf.get_u8();
16900 __struct.bus = buf.get_u8();
16901 let tmp = buf.get_u8();
16902 __struct.operation =
16903 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16904 enum_type: "CanFilterOp",
16905 value: tmp as u32,
16906 })?;
16907 __struct.num_ids = buf.get_u8();
16908 Ok(__struct)
16909 }
16910 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16911 let mut __tmp = BytesMut::new(bytes);
16912 #[allow(clippy::absurd_extreme_comparisons)]
16913 #[allow(unused_comparisons)]
16914 if __tmp.remaining() < Self::ENCODED_LEN {
16915 panic!(
16916 "buffer is too small (need {} bytes, but got {})",
16917 Self::ENCODED_LEN,
16918 __tmp.remaining(),
16919 )
16920 }
16921 for val in &self.ids {
16922 __tmp.put_u16_le(*val);
16923 }
16924 __tmp.put_u8(self.target_system);
16925 __tmp.put_u8(self.target_component);
16926 __tmp.put_u8(self.bus);
16927 __tmp.put_u8(self.operation as u8);
16928 __tmp.put_u8(self.num_ids);
16929 if matches!(version, MavlinkVersion::V2) {
16930 let len = __tmp.len();
16931 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16932 } else {
16933 __tmp.len()
16934 }
16935 }
16936}
16937#[doc = "id: 245"]
16938#[doc = "Provides state for additional features."]
16939#[derive(Debug, Clone, PartialEq)]
16940#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16941#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16942pub struct EXTENDED_SYS_STATE_DATA {
16943 #[doc = "The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration."]
16944 pub vtol_state: MavVtolState,
16945 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
16946 pub landed_state: MavLandedState,
16947}
16948impl EXTENDED_SYS_STATE_DATA {
16949 pub const ENCODED_LEN: usize = 2usize;
16950 pub const DEFAULT: Self = Self {
16951 vtol_state: MavVtolState::DEFAULT,
16952 landed_state: MavLandedState::DEFAULT,
16953 };
16954 #[cfg(feature = "arbitrary")]
16955 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16956 use arbitrary::{Arbitrary, Unstructured};
16957 let mut buf = [0u8; 1024];
16958 rng.fill_bytes(&mut buf);
16959 let mut unstructured = Unstructured::new(&buf);
16960 Self::arbitrary(&mut unstructured).unwrap_or_default()
16961 }
16962}
16963impl Default for EXTENDED_SYS_STATE_DATA {
16964 fn default() -> Self {
16965 Self::DEFAULT.clone()
16966 }
16967}
16968impl MessageData for EXTENDED_SYS_STATE_DATA {
16969 type Message = MavMessage;
16970 const ID: u32 = 245u32;
16971 const NAME: &'static str = "EXTENDED_SYS_STATE";
16972 const EXTRA_CRC: u8 = 130u8;
16973 const ENCODED_LEN: usize = 2usize;
16974 fn deser(
16975 _version: MavlinkVersion,
16976 __input: &[u8],
16977 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16978 let avail_len = __input.len();
16979 let mut payload_buf = [0; Self::ENCODED_LEN];
16980 let mut buf = if avail_len < Self::ENCODED_LEN {
16981 payload_buf[0..avail_len].copy_from_slice(__input);
16982 Bytes::new(&payload_buf)
16983 } else {
16984 Bytes::new(__input)
16985 };
16986 let mut __struct = Self::default();
16987 let tmp = buf.get_u8();
16988 __struct.vtol_state =
16989 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16990 enum_type: "MavVtolState",
16991 value: tmp as u32,
16992 })?;
16993 let tmp = buf.get_u8();
16994 __struct.landed_state =
16995 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16996 enum_type: "MavLandedState",
16997 value: tmp as u32,
16998 })?;
16999 Ok(__struct)
17000 }
17001 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17002 let mut __tmp = BytesMut::new(bytes);
17003 #[allow(clippy::absurd_extreme_comparisons)]
17004 #[allow(unused_comparisons)]
17005 if __tmp.remaining() < Self::ENCODED_LEN {
17006 panic!(
17007 "buffer is too small (need {} bytes, but got {})",
17008 Self::ENCODED_LEN,
17009 __tmp.remaining(),
17010 )
17011 }
17012 __tmp.put_u8(self.vtol_state as u8);
17013 __tmp.put_u8(self.landed_state as u8);
17014 if matches!(version, MavlinkVersion::V2) {
17015 let len = __tmp.len();
17016 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17017 } else {
17018 __tmp.len()
17019 }
17020 }
17021}
17022#[doc = "id: 10006"]
17023#[doc = "Request messages."]
17024#[derive(Debug, Clone, PartialEq)]
17025#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17026#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17027pub struct UAVIONIX_ADSB_GET_DATA {
17028 #[doc = "Message ID to request. Supports any message in this 10000-10099 range"]
17029 pub ReqMessageId: u32,
17030}
17031impl UAVIONIX_ADSB_GET_DATA {
17032 pub const ENCODED_LEN: usize = 4usize;
17033 pub const DEFAULT: Self = Self {
17034 ReqMessageId: 0_u32,
17035 };
17036 #[cfg(feature = "arbitrary")]
17037 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17038 use arbitrary::{Arbitrary, Unstructured};
17039 let mut buf = [0u8; 1024];
17040 rng.fill_bytes(&mut buf);
17041 let mut unstructured = Unstructured::new(&buf);
17042 Self::arbitrary(&mut unstructured).unwrap_or_default()
17043 }
17044}
17045impl Default for UAVIONIX_ADSB_GET_DATA {
17046 fn default() -> Self {
17047 Self::DEFAULT.clone()
17048 }
17049}
17050impl MessageData for UAVIONIX_ADSB_GET_DATA {
17051 type Message = MavMessage;
17052 const ID: u32 = 10006u32;
17053 const NAME: &'static str = "UAVIONIX_ADSB_GET";
17054 const EXTRA_CRC: u8 = 193u8;
17055 const ENCODED_LEN: usize = 4usize;
17056 fn deser(
17057 _version: MavlinkVersion,
17058 __input: &[u8],
17059 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17060 let avail_len = __input.len();
17061 let mut payload_buf = [0; Self::ENCODED_LEN];
17062 let mut buf = if avail_len < Self::ENCODED_LEN {
17063 payload_buf[0..avail_len].copy_from_slice(__input);
17064 Bytes::new(&payload_buf)
17065 } else {
17066 Bytes::new(__input)
17067 };
17068 let mut __struct = Self::default();
17069 __struct.ReqMessageId = buf.get_u32_le();
17070 Ok(__struct)
17071 }
17072 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17073 let mut __tmp = BytesMut::new(bytes);
17074 #[allow(clippy::absurd_extreme_comparisons)]
17075 #[allow(unused_comparisons)]
17076 if __tmp.remaining() < Self::ENCODED_LEN {
17077 panic!(
17078 "buffer is too small (need {} bytes, but got {})",
17079 Self::ENCODED_LEN,
17080 __tmp.remaining(),
17081 )
17082 }
17083 __tmp.put_u32_le(self.ReqMessageId);
17084 if matches!(version, MavlinkVersion::V2) {
17085 let len = __tmp.len();
17086 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17087 } else {
17088 __tmp.len()
17089 }
17090 }
17091}
17092#[doc = "id: 401"]
17093#[doc = "Tune formats supported by vehicle. This should be emitted as response to MAV_CMD_REQUEST_MESSAGE."]
17094#[derive(Debug, Clone, PartialEq)]
17095#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17096#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17097pub struct SUPPORTED_TUNES_DATA {
17098 #[doc = "Bitfield of supported tune formats."]
17099 pub format: TuneFormat,
17100 #[doc = "System ID"]
17101 pub target_system: u8,
17102 #[doc = "Component ID"]
17103 pub target_component: u8,
17104}
17105impl SUPPORTED_TUNES_DATA {
17106 pub const ENCODED_LEN: usize = 6usize;
17107 pub const DEFAULT: Self = Self {
17108 format: TuneFormat::DEFAULT,
17109 target_system: 0_u8,
17110 target_component: 0_u8,
17111 };
17112 #[cfg(feature = "arbitrary")]
17113 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17114 use arbitrary::{Arbitrary, Unstructured};
17115 let mut buf = [0u8; 1024];
17116 rng.fill_bytes(&mut buf);
17117 let mut unstructured = Unstructured::new(&buf);
17118 Self::arbitrary(&mut unstructured).unwrap_or_default()
17119 }
17120}
17121impl Default for SUPPORTED_TUNES_DATA {
17122 fn default() -> Self {
17123 Self::DEFAULT.clone()
17124 }
17125}
17126impl MessageData for SUPPORTED_TUNES_DATA {
17127 type Message = MavMessage;
17128 const ID: u32 = 401u32;
17129 const NAME: &'static str = "SUPPORTED_TUNES";
17130 const EXTRA_CRC: u8 = 183u8;
17131 const ENCODED_LEN: usize = 6usize;
17132 fn deser(
17133 _version: MavlinkVersion,
17134 __input: &[u8],
17135 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17136 let avail_len = __input.len();
17137 let mut payload_buf = [0; Self::ENCODED_LEN];
17138 let mut buf = if avail_len < Self::ENCODED_LEN {
17139 payload_buf[0..avail_len].copy_from_slice(__input);
17140 Bytes::new(&payload_buf)
17141 } else {
17142 Bytes::new(__input)
17143 };
17144 let mut __struct = Self::default();
17145 let tmp = buf.get_u32_le();
17146 __struct.format = FromPrimitive::from_u32(tmp).ok_or(
17147 ::mavlink_core::error::ParserError::InvalidEnum {
17148 enum_type: "TuneFormat",
17149 value: tmp as u32,
17150 },
17151 )?;
17152 __struct.target_system = buf.get_u8();
17153 __struct.target_component = buf.get_u8();
17154 Ok(__struct)
17155 }
17156 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17157 let mut __tmp = BytesMut::new(bytes);
17158 #[allow(clippy::absurd_extreme_comparisons)]
17159 #[allow(unused_comparisons)]
17160 if __tmp.remaining() < Self::ENCODED_LEN {
17161 panic!(
17162 "buffer is too small (need {} bytes, but got {})",
17163 Self::ENCODED_LEN,
17164 __tmp.remaining(),
17165 )
17166 }
17167 __tmp.put_u32_le(self.format as u32);
17168 __tmp.put_u8(self.target_system);
17169 __tmp.put_u8(self.target_component);
17170 if matches!(version, MavlinkVersion::V2) {
17171 let len = __tmp.len();
17172 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17173 } else {
17174 __tmp.len()
17175 }
17176 }
17177}
17178#[doc = "id: 130"]
17179#[doc = "Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: <https://mavlink.io/en/services/image_transmission.html>."]
17180#[derive(Debug, Clone, PartialEq)]
17181#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17182#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17183pub struct DATA_TRANSMISSION_HANDSHAKE_DATA {
17184 #[doc = "total data size (set on ACK only)."]
17185 pub size: u32,
17186 #[doc = "Width of a matrix or image."]
17187 pub width: u16,
17188 #[doc = "Height of a matrix or image."]
17189 pub height: u16,
17190 #[doc = "Number of packets being sent (set on ACK only)."]
17191 pub packets: u16,
17192 #[doc = "Type of requested/acknowledged data."]
17193 pub mavtype: MavlinkDataStreamType,
17194 #[doc = "Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)."]
17195 pub payload: u8,
17196 #[doc = "JPEG quality. Values: [1-100]."]
17197 pub jpg_quality: u8,
17198}
17199impl DATA_TRANSMISSION_HANDSHAKE_DATA {
17200 pub const ENCODED_LEN: usize = 13usize;
17201 pub const DEFAULT: Self = Self {
17202 size: 0_u32,
17203 width: 0_u16,
17204 height: 0_u16,
17205 packets: 0_u16,
17206 mavtype: MavlinkDataStreamType::DEFAULT,
17207 payload: 0_u8,
17208 jpg_quality: 0_u8,
17209 };
17210 #[cfg(feature = "arbitrary")]
17211 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17212 use arbitrary::{Arbitrary, Unstructured};
17213 let mut buf = [0u8; 1024];
17214 rng.fill_bytes(&mut buf);
17215 let mut unstructured = Unstructured::new(&buf);
17216 Self::arbitrary(&mut unstructured).unwrap_or_default()
17217 }
17218}
17219impl Default for DATA_TRANSMISSION_HANDSHAKE_DATA {
17220 fn default() -> Self {
17221 Self::DEFAULT.clone()
17222 }
17223}
17224impl MessageData for DATA_TRANSMISSION_HANDSHAKE_DATA {
17225 type Message = MavMessage;
17226 const ID: u32 = 130u32;
17227 const NAME: &'static str = "DATA_TRANSMISSION_HANDSHAKE";
17228 const EXTRA_CRC: u8 = 29u8;
17229 const ENCODED_LEN: usize = 13usize;
17230 fn deser(
17231 _version: MavlinkVersion,
17232 __input: &[u8],
17233 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17234 let avail_len = __input.len();
17235 let mut payload_buf = [0; Self::ENCODED_LEN];
17236 let mut buf = if avail_len < Self::ENCODED_LEN {
17237 payload_buf[0..avail_len].copy_from_slice(__input);
17238 Bytes::new(&payload_buf)
17239 } else {
17240 Bytes::new(__input)
17241 };
17242 let mut __struct = Self::default();
17243 __struct.size = buf.get_u32_le();
17244 __struct.width = buf.get_u16_le();
17245 __struct.height = buf.get_u16_le();
17246 __struct.packets = buf.get_u16_le();
17247 let tmp = buf.get_u8();
17248 __struct.mavtype =
17249 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17250 enum_type: "MavlinkDataStreamType",
17251 value: tmp as u32,
17252 })?;
17253 __struct.payload = buf.get_u8();
17254 __struct.jpg_quality = buf.get_u8();
17255 Ok(__struct)
17256 }
17257 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17258 let mut __tmp = BytesMut::new(bytes);
17259 #[allow(clippy::absurd_extreme_comparisons)]
17260 #[allow(unused_comparisons)]
17261 if __tmp.remaining() < Self::ENCODED_LEN {
17262 panic!(
17263 "buffer is too small (need {} bytes, but got {})",
17264 Self::ENCODED_LEN,
17265 __tmp.remaining(),
17266 )
17267 }
17268 __tmp.put_u32_le(self.size);
17269 __tmp.put_u16_le(self.width);
17270 __tmp.put_u16_le(self.height);
17271 __tmp.put_u16_le(self.packets);
17272 __tmp.put_u8(self.mavtype as u8);
17273 __tmp.put_u8(self.payload);
17274 __tmp.put_u8(self.jpg_quality);
17275 if matches!(version, MavlinkVersion::V2) {
17276 let len = __tmp.len();
17277 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17278 } else {
17279 __tmp.len()
17280 }
17281 }
17282}
17283#[doc = "id: 323"]
17284#[doc = "Set a parameter value. In order to deal with message loss (and retransmission of PARAM_EXT_SET), when setting a parameter value and the new value is the same as the current value, you will immediately get a PARAM_ACK_ACCEPTED response. If the current state is PARAM_ACK_IN_PROGRESS, you will accordingly receive a PARAM_ACK_IN_PROGRESS in response."]
17285#[derive(Debug, Clone, PartialEq)]
17286#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17287#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17288pub struct PARAM_EXT_SET_DATA {
17289 #[doc = "System ID"]
17290 pub target_system: u8,
17291 #[doc = "Component ID"]
17292 pub target_component: u8,
17293 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
17294 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17295 pub param_id: [u8; 16],
17296 #[doc = "Parameter value"]
17297 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17298 pub param_value: [u8; 128],
17299 #[doc = "Parameter type."]
17300 pub param_type: MavParamExtType,
17301}
17302impl PARAM_EXT_SET_DATA {
17303 pub const ENCODED_LEN: usize = 147usize;
17304 pub const DEFAULT: Self = Self {
17305 target_system: 0_u8,
17306 target_component: 0_u8,
17307 param_id: [0_u8; 16usize],
17308 param_value: [0_u8; 128usize],
17309 param_type: MavParamExtType::DEFAULT,
17310 };
17311 #[cfg(feature = "arbitrary")]
17312 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17313 use arbitrary::{Arbitrary, Unstructured};
17314 let mut buf = [0u8; 1024];
17315 rng.fill_bytes(&mut buf);
17316 let mut unstructured = Unstructured::new(&buf);
17317 Self::arbitrary(&mut unstructured).unwrap_or_default()
17318 }
17319}
17320impl Default for PARAM_EXT_SET_DATA {
17321 fn default() -> Self {
17322 Self::DEFAULT.clone()
17323 }
17324}
17325impl MessageData for PARAM_EXT_SET_DATA {
17326 type Message = MavMessage;
17327 const ID: u32 = 323u32;
17328 const NAME: &'static str = "PARAM_EXT_SET";
17329 const EXTRA_CRC: u8 = 78u8;
17330 const ENCODED_LEN: usize = 147usize;
17331 fn deser(
17332 _version: MavlinkVersion,
17333 __input: &[u8],
17334 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17335 let avail_len = __input.len();
17336 let mut payload_buf = [0; Self::ENCODED_LEN];
17337 let mut buf = if avail_len < Self::ENCODED_LEN {
17338 payload_buf[0..avail_len].copy_from_slice(__input);
17339 Bytes::new(&payload_buf)
17340 } else {
17341 Bytes::new(__input)
17342 };
17343 let mut __struct = Self::default();
17344 __struct.target_system = buf.get_u8();
17345 __struct.target_component = buf.get_u8();
17346 for v in &mut __struct.param_id {
17347 let val = buf.get_u8();
17348 *v = val;
17349 }
17350 for v in &mut __struct.param_value {
17351 let val = buf.get_u8();
17352 *v = val;
17353 }
17354 let tmp = buf.get_u8();
17355 __struct.param_type =
17356 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17357 enum_type: "MavParamExtType",
17358 value: tmp as u32,
17359 })?;
17360 Ok(__struct)
17361 }
17362 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17363 let mut __tmp = BytesMut::new(bytes);
17364 #[allow(clippy::absurd_extreme_comparisons)]
17365 #[allow(unused_comparisons)]
17366 if __tmp.remaining() < Self::ENCODED_LEN {
17367 panic!(
17368 "buffer is too small (need {} bytes, but got {})",
17369 Self::ENCODED_LEN,
17370 __tmp.remaining(),
17371 )
17372 }
17373 __tmp.put_u8(self.target_system);
17374 __tmp.put_u8(self.target_component);
17375 for val in &self.param_id {
17376 __tmp.put_u8(*val);
17377 }
17378 for val in &self.param_value {
17379 __tmp.put_u8(*val);
17380 }
17381 __tmp.put_u8(self.param_type as u8);
17382 if matches!(version, MavlinkVersion::V2) {
17383 let len = __tmp.len();
17384 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17385 } else {
17386 __tmp.len()
17387 }
17388 }
17389}
17390#[doc = "id: 263"]
17391#[doc = "Information about a captured image. This is emitted every time a message is captured. MAV_CMD_REQUEST_MESSAGE can be used to (re)request this message for a specific sequence number or range of sequence numbers: MAV_CMD_REQUEST_MESSAGE.param2 indicates the sequence number the first image to send, or set to -1 to send the message for all sequence numbers. MAV_CMD_REQUEST_MESSAGE.param3 is used to specify a range of messages to send: set to 0 (default) to send just the the message for the sequence number in param 2, set to -1 to send the message for the sequence number in param 2 and all the following sequence numbers, set to the sequence number of the final message in the range."]
17392#[derive(Debug, Clone, PartialEq)]
17393#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17394#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17395pub struct CAMERA_IMAGE_CAPTURED_DATA {
17396 #[doc = "Timestamp (time since UNIX epoch) in UTC. 0 for unknown."]
17397 pub time_utc: u64,
17398 #[doc = "Timestamp (time since system boot)."]
17399 pub time_boot_ms: u32,
17400 #[doc = "Latitude where image was taken"]
17401 pub lat: i32,
17402 #[doc = "Longitude where capture was taken"]
17403 pub lon: i32,
17404 #[doc = "Altitude (MSL) where image was taken"]
17405 pub alt: i32,
17406 #[doc = "Altitude above ground"]
17407 pub relative_alt: i32,
17408 #[doc = "Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
17409 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17410 pub q: [f32; 4],
17411 #[doc = "Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)"]
17412 pub image_index: i32,
17413 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). Field name is usually camera_device_id."]
17414 pub camera_id: u8,
17415 #[doc = "Boolean indicating success (1) or failure (0) while capturing this image."]
17416 pub capture_result: i8,
17417 #[doc = "URL of image taken. Either local storage or <http://foo.jpg> if camera provides an HTTP interface."]
17418 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17419 pub file_url: [u8; 205],
17420}
17421impl CAMERA_IMAGE_CAPTURED_DATA {
17422 pub const ENCODED_LEN: usize = 255usize;
17423 pub const DEFAULT: Self = Self {
17424 time_utc: 0_u64,
17425 time_boot_ms: 0_u32,
17426 lat: 0_i32,
17427 lon: 0_i32,
17428 alt: 0_i32,
17429 relative_alt: 0_i32,
17430 q: [0.0_f32; 4usize],
17431 image_index: 0_i32,
17432 camera_id: 0_u8,
17433 capture_result: 0_i8,
17434 file_url: [0_u8; 205usize],
17435 };
17436 #[cfg(feature = "arbitrary")]
17437 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17438 use arbitrary::{Arbitrary, Unstructured};
17439 let mut buf = [0u8; 1024];
17440 rng.fill_bytes(&mut buf);
17441 let mut unstructured = Unstructured::new(&buf);
17442 Self::arbitrary(&mut unstructured).unwrap_or_default()
17443 }
17444}
17445impl Default for CAMERA_IMAGE_CAPTURED_DATA {
17446 fn default() -> Self {
17447 Self::DEFAULT.clone()
17448 }
17449}
17450impl MessageData for CAMERA_IMAGE_CAPTURED_DATA {
17451 type Message = MavMessage;
17452 const ID: u32 = 263u32;
17453 const NAME: &'static str = "CAMERA_IMAGE_CAPTURED";
17454 const EXTRA_CRC: u8 = 133u8;
17455 const ENCODED_LEN: usize = 255usize;
17456 fn deser(
17457 _version: MavlinkVersion,
17458 __input: &[u8],
17459 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17460 let avail_len = __input.len();
17461 let mut payload_buf = [0; Self::ENCODED_LEN];
17462 let mut buf = if avail_len < Self::ENCODED_LEN {
17463 payload_buf[0..avail_len].copy_from_slice(__input);
17464 Bytes::new(&payload_buf)
17465 } else {
17466 Bytes::new(__input)
17467 };
17468 let mut __struct = Self::default();
17469 __struct.time_utc = buf.get_u64_le();
17470 __struct.time_boot_ms = buf.get_u32_le();
17471 __struct.lat = buf.get_i32_le();
17472 __struct.lon = buf.get_i32_le();
17473 __struct.alt = buf.get_i32_le();
17474 __struct.relative_alt = buf.get_i32_le();
17475 for v in &mut __struct.q {
17476 let val = buf.get_f32_le();
17477 *v = val;
17478 }
17479 __struct.image_index = buf.get_i32_le();
17480 __struct.camera_id = buf.get_u8();
17481 __struct.capture_result = buf.get_i8();
17482 for v in &mut __struct.file_url {
17483 let val = buf.get_u8();
17484 *v = val;
17485 }
17486 Ok(__struct)
17487 }
17488 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17489 let mut __tmp = BytesMut::new(bytes);
17490 #[allow(clippy::absurd_extreme_comparisons)]
17491 #[allow(unused_comparisons)]
17492 if __tmp.remaining() < Self::ENCODED_LEN {
17493 panic!(
17494 "buffer is too small (need {} bytes, but got {})",
17495 Self::ENCODED_LEN,
17496 __tmp.remaining(),
17497 )
17498 }
17499 __tmp.put_u64_le(self.time_utc);
17500 __tmp.put_u32_le(self.time_boot_ms);
17501 __tmp.put_i32_le(self.lat);
17502 __tmp.put_i32_le(self.lon);
17503 __tmp.put_i32_le(self.alt);
17504 __tmp.put_i32_le(self.relative_alt);
17505 for val in &self.q {
17506 __tmp.put_f32_le(*val);
17507 }
17508 __tmp.put_i32_le(self.image_index);
17509 __tmp.put_u8(self.camera_id);
17510 __tmp.put_i8(self.capture_result);
17511 for val in &self.file_url {
17512 __tmp.put_u8(*val);
17513 }
17514 if matches!(version, MavlinkVersion::V2) {
17515 let len = __tmp.len();
17516 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17517 } else {
17518 __tmp.len()
17519 }
17520 }
17521}
17522#[doc = "id: 412"]
17523#[doc = "Request one or more events to be (re-)sent. If first_sequence==last_sequence, only a single event is requested. Note that first_sequence can be larger than last_sequence (because the sequence number can wrap). Each sequence will trigger an EVENT or EVENT_ERROR response."]
17524#[derive(Debug, Clone, PartialEq)]
17525#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17526#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17527pub struct REQUEST_EVENT_DATA {
17528 #[doc = "First sequence number of the requested event."]
17529 pub first_sequence: u16,
17530 #[doc = "Last sequence number of the requested event."]
17531 pub last_sequence: u16,
17532 #[doc = "System ID"]
17533 pub target_system: u8,
17534 #[doc = "Component ID"]
17535 pub target_component: u8,
17536}
17537impl REQUEST_EVENT_DATA {
17538 pub const ENCODED_LEN: usize = 6usize;
17539 pub const DEFAULT: Self = Self {
17540 first_sequence: 0_u16,
17541 last_sequence: 0_u16,
17542 target_system: 0_u8,
17543 target_component: 0_u8,
17544 };
17545 #[cfg(feature = "arbitrary")]
17546 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17547 use arbitrary::{Arbitrary, Unstructured};
17548 let mut buf = [0u8; 1024];
17549 rng.fill_bytes(&mut buf);
17550 let mut unstructured = Unstructured::new(&buf);
17551 Self::arbitrary(&mut unstructured).unwrap_or_default()
17552 }
17553}
17554impl Default for REQUEST_EVENT_DATA {
17555 fn default() -> Self {
17556 Self::DEFAULT.clone()
17557 }
17558}
17559impl MessageData for REQUEST_EVENT_DATA {
17560 type Message = MavMessage;
17561 const ID: u32 = 412u32;
17562 const NAME: &'static str = "REQUEST_EVENT";
17563 const EXTRA_CRC: u8 = 33u8;
17564 const ENCODED_LEN: usize = 6usize;
17565 fn deser(
17566 _version: MavlinkVersion,
17567 __input: &[u8],
17568 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17569 let avail_len = __input.len();
17570 let mut payload_buf = [0; Self::ENCODED_LEN];
17571 let mut buf = if avail_len < Self::ENCODED_LEN {
17572 payload_buf[0..avail_len].copy_from_slice(__input);
17573 Bytes::new(&payload_buf)
17574 } else {
17575 Bytes::new(__input)
17576 };
17577 let mut __struct = Self::default();
17578 __struct.first_sequence = buf.get_u16_le();
17579 __struct.last_sequence = buf.get_u16_le();
17580 __struct.target_system = buf.get_u8();
17581 __struct.target_component = buf.get_u8();
17582 Ok(__struct)
17583 }
17584 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17585 let mut __tmp = BytesMut::new(bytes);
17586 #[allow(clippy::absurd_extreme_comparisons)]
17587 #[allow(unused_comparisons)]
17588 if __tmp.remaining() < Self::ENCODED_LEN {
17589 panic!(
17590 "buffer is too small (need {} bytes, but got {})",
17591 Self::ENCODED_LEN,
17592 __tmp.remaining(),
17593 )
17594 }
17595 __tmp.put_u16_le(self.first_sequence);
17596 __tmp.put_u16_le(self.last_sequence);
17597 __tmp.put_u8(self.target_system);
17598 __tmp.put_u8(self.target_component);
17599 if matches!(version, MavlinkVersion::V2) {
17600 let len = __tmp.len();
17601 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17602 } else {
17603 __tmp.len()
17604 }
17605 }
17606}
17607#[doc = "id: 63"]
17608#[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset."]
17609#[derive(Debug, Clone, PartialEq)]
17610#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17611#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17612pub struct GLOBAL_POSITION_INT_COV_DATA {
17613 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
17614 pub time_usec: u64,
17615 #[doc = "Latitude"]
17616 pub lat: i32,
17617 #[doc = "Longitude"]
17618 pub lon: i32,
17619 #[doc = "Altitude in meters above MSL"]
17620 pub alt: i32,
17621 #[doc = "Altitude above ground"]
17622 pub relative_alt: i32,
17623 #[doc = "Ground X Speed (Latitude)"]
17624 pub vx: f32,
17625 #[doc = "Ground Y Speed (Longitude)"]
17626 pub vy: f32,
17627 #[doc = "Ground Z Speed (Altitude)"]
17628 pub vz: f32,
17629 #[doc = "Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
17630 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17631 pub covariance: [f32; 36],
17632 #[doc = "Class id of the estimator this estimate originated from."]
17633 pub estimator_type: MavEstimatorType,
17634}
17635impl GLOBAL_POSITION_INT_COV_DATA {
17636 pub const ENCODED_LEN: usize = 181usize;
17637 pub const DEFAULT: Self = Self {
17638 time_usec: 0_u64,
17639 lat: 0_i32,
17640 lon: 0_i32,
17641 alt: 0_i32,
17642 relative_alt: 0_i32,
17643 vx: 0.0_f32,
17644 vy: 0.0_f32,
17645 vz: 0.0_f32,
17646 covariance: [0.0_f32; 36usize],
17647 estimator_type: MavEstimatorType::DEFAULT,
17648 };
17649 #[cfg(feature = "arbitrary")]
17650 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17651 use arbitrary::{Arbitrary, Unstructured};
17652 let mut buf = [0u8; 1024];
17653 rng.fill_bytes(&mut buf);
17654 let mut unstructured = Unstructured::new(&buf);
17655 Self::arbitrary(&mut unstructured).unwrap_or_default()
17656 }
17657}
17658impl Default for GLOBAL_POSITION_INT_COV_DATA {
17659 fn default() -> Self {
17660 Self::DEFAULT.clone()
17661 }
17662}
17663impl MessageData for GLOBAL_POSITION_INT_COV_DATA {
17664 type Message = MavMessage;
17665 const ID: u32 = 63u32;
17666 const NAME: &'static str = "GLOBAL_POSITION_INT_COV";
17667 const EXTRA_CRC: u8 = 119u8;
17668 const ENCODED_LEN: usize = 181usize;
17669 fn deser(
17670 _version: MavlinkVersion,
17671 __input: &[u8],
17672 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17673 let avail_len = __input.len();
17674 let mut payload_buf = [0; Self::ENCODED_LEN];
17675 let mut buf = if avail_len < Self::ENCODED_LEN {
17676 payload_buf[0..avail_len].copy_from_slice(__input);
17677 Bytes::new(&payload_buf)
17678 } else {
17679 Bytes::new(__input)
17680 };
17681 let mut __struct = Self::default();
17682 __struct.time_usec = buf.get_u64_le();
17683 __struct.lat = buf.get_i32_le();
17684 __struct.lon = buf.get_i32_le();
17685 __struct.alt = buf.get_i32_le();
17686 __struct.relative_alt = buf.get_i32_le();
17687 __struct.vx = buf.get_f32_le();
17688 __struct.vy = buf.get_f32_le();
17689 __struct.vz = buf.get_f32_le();
17690 for v in &mut __struct.covariance {
17691 let val = buf.get_f32_le();
17692 *v = val;
17693 }
17694 let tmp = buf.get_u8();
17695 __struct.estimator_type =
17696 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17697 enum_type: "MavEstimatorType",
17698 value: tmp as u32,
17699 })?;
17700 Ok(__struct)
17701 }
17702 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17703 let mut __tmp = BytesMut::new(bytes);
17704 #[allow(clippy::absurd_extreme_comparisons)]
17705 #[allow(unused_comparisons)]
17706 if __tmp.remaining() < Self::ENCODED_LEN {
17707 panic!(
17708 "buffer is too small (need {} bytes, but got {})",
17709 Self::ENCODED_LEN,
17710 __tmp.remaining(),
17711 )
17712 }
17713 __tmp.put_u64_le(self.time_usec);
17714 __tmp.put_i32_le(self.lat);
17715 __tmp.put_i32_le(self.lon);
17716 __tmp.put_i32_le(self.alt);
17717 __tmp.put_i32_le(self.relative_alt);
17718 __tmp.put_f32_le(self.vx);
17719 __tmp.put_f32_le(self.vy);
17720 __tmp.put_f32_le(self.vz);
17721 for val in &self.covariance {
17722 __tmp.put_f32_le(*val);
17723 }
17724 __tmp.put_u8(self.estimator_type as u8);
17725 if matches!(version, MavlinkVersion::V2) {
17726 let len = __tmp.len();
17727 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17728 } else {
17729 __tmp.len()
17730 }
17731 }
17732}
17733#[doc = "id: 22"]
17734#[doc = "Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
17735#[derive(Debug, Clone, PartialEq)]
17736#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17737#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17738pub struct PARAM_VALUE_DATA {
17739 #[doc = "Onboard parameter value"]
17740 pub param_value: f32,
17741 #[doc = "Total number of onboard parameters"]
17742 pub param_count: u16,
17743 #[doc = "Index of this onboard parameter"]
17744 pub param_index: u16,
17745 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
17746 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17747 pub param_id: [u8; 16],
17748 #[doc = "Onboard parameter type."]
17749 pub param_type: MavParamType,
17750}
17751impl PARAM_VALUE_DATA {
17752 pub const ENCODED_LEN: usize = 25usize;
17753 pub const DEFAULT: Self = Self {
17754 param_value: 0.0_f32,
17755 param_count: 0_u16,
17756 param_index: 0_u16,
17757 param_id: [0_u8; 16usize],
17758 param_type: MavParamType::DEFAULT,
17759 };
17760 #[cfg(feature = "arbitrary")]
17761 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17762 use arbitrary::{Arbitrary, Unstructured};
17763 let mut buf = [0u8; 1024];
17764 rng.fill_bytes(&mut buf);
17765 let mut unstructured = Unstructured::new(&buf);
17766 Self::arbitrary(&mut unstructured).unwrap_or_default()
17767 }
17768}
17769impl Default for PARAM_VALUE_DATA {
17770 fn default() -> Self {
17771 Self::DEFAULT.clone()
17772 }
17773}
17774impl MessageData for PARAM_VALUE_DATA {
17775 type Message = MavMessage;
17776 const ID: u32 = 22u32;
17777 const NAME: &'static str = "PARAM_VALUE";
17778 const EXTRA_CRC: u8 = 220u8;
17779 const ENCODED_LEN: usize = 25usize;
17780 fn deser(
17781 _version: MavlinkVersion,
17782 __input: &[u8],
17783 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17784 let avail_len = __input.len();
17785 let mut payload_buf = [0; Self::ENCODED_LEN];
17786 let mut buf = if avail_len < Self::ENCODED_LEN {
17787 payload_buf[0..avail_len].copy_from_slice(__input);
17788 Bytes::new(&payload_buf)
17789 } else {
17790 Bytes::new(__input)
17791 };
17792 let mut __struct = Self::default();
17793 __struct.param_value = buf.get_f32_le();
17794 __struct.param_count = buf.get_u16_le();
17795 __struct.param_index = buf.get_u16_le();
17796 for v in &mut __struct.param_id {
17797 let val = buf.get_u8();
17798 *v = val;
17799 }
17800 let tmp = buf.get_u8();
17801 __struct.param_type =
17802 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17803 enum_type: "MavParamType",
17804 value: tmp as u32,
17805 })?;
17806 Ok(__struct)
17807 }
17808 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17809 let mut __tmp = BytesMut::new(bytes);
17810 #[allow(clippy::absurd_extreme_comparisons)]
17811 #[allow(unused_comparisons)]
17812 if __tmp.remaining() < Self::ENCODED_LEN {
17813 panic!(
17814 "buffer is too small (need {} bytes, but got {})",
17815 Self::ENCODED_LEN,
17816 __tmp.remaining(),
17817 )
17818 }
17819 __tmp.put_f32_le(self.param_value);
17820 __tmp.put_u16_le(self.param_count);
17821 __tmp.put_u16_le(self.param_index);
17822 for val in &self.param_id {
17823 __tmp.put_u8(*val);
17824 }
17825 __tmp.put_u8(self.param_type as u8);
17826 if matches!(version, MavlinkVersion::V2) {
17827 let len = __tmp.len();
17828 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17829 } else {
17830 __tmp.len()
17831 }
17832 }
17833}
17834#[doc = "id: 192"]
17835#[doc = "Reports results of completed compass calibration. Sent until MAG_CAL_ACK received."]
17836#[derive(Debug, Clone, PartialEq)]
17837#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17838#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17839pub struct MAG_CAL_REPORT_DATA {
17840 #[doc = "RMS milligauss residuals."]
17841 pub fitness: f32,
17842 #[doc = "X offset."]
17843 pub ofs_x: f32,
17844 #[doc = "Y offset."]
17845 pub ofs_y: f32,
17846 #[doc = "Z offset."]
17847 pub ofs_z: f32,
17848 #[doc = "X diagonal (matrix 11)."]
17849 pub diag_x: f32,
17850 #[doc = "Y diagonal (matrix 22)."]
17851 pub diag_y: f32,
17852 #[doc = "Z diagonal (matrix 33)."]
17853 pub diag_z: f32,
17854 #[doc = "X off-diagonal (matrix 12 and 21)."]
17855 pub offdiag_x: f32,
17856 #[doc = "Y off-diagonal (matrix 13 and 31)."]
17857 pub offdiag_y: f32,
17858 #[doc = "Z off-diagonal (matrix 32 and 23)."]
17859 pub offdiag_z: f32,
17860 #[doc = "Compass being calibrated."]
17861 pub compass_id: u8,
17862 #[doc = "Bitmask of compasses being calibrated."]
17863 pub cal_mask: u8,
17864 #[doc = "Calibration Status."]
17865 pub cal_status: MagCalStatus,
17866 #[doc = "0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters."]
17867 pub autosaved: u8,
17868 #[doc = "Confidence in orientation (higher is better)."]
17869 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17870 pub orientation_confidence: f32,
17871 #[doc = "orientation before calibration."]
17872 #[cfg_attr(feature = "serde", serde(default))]
17873 pub old_orientation: MavSensorOrientation,
17874 #[doc = "orientation after calibration."]
17875 #[cfg_attr(feature = "serde", serde(default))]
17876 pub new_orientation: MavSensorOrientation,
17877 #[doc = "field radius correction factor"]
17878 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17879 pub scale_factor: f32,
17880}
17881impl MAG_CAL_REPORT_DATA {
17882 pub const ENCODED_LEN: usize = 54usize;
17883 pub const DEFAULT: Self = Self {
17884 fitness: 0.0_f32,
17885 ofs_x: 0.0_f32,
17886 ofs_y: 0.0_f32,
17887 ofs_z: 0.0_f32,
17888 diag_x: 0.0_f32,
17889 diag_y: 0.0_f32,
17890 diag_z: 0.0_f32,
17891 offdiag_x: 0.0_f32,
17892 offdiag_y: 0.0_f32,
17893 offdiag_z: 0.0_f32,
17894 compass_id: 0_u8,
17895 cal_mask: 0_u8,
17896 cal_status: MagCalStatus::DEFAULT,
17897 autosaved: 0_u8,
17898 orientation_confidence: 0.0_f32,
17899 old_orientation: MavSensorOrientation::DEFAULT,
17900 new_orientation: MavSensorOrientation::DEFAULT,
17901 scale_factor: 0.0_f32,
17902 };
17903 #[cfg(feature = "arbitrary")]
17904 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17905 use arbitrary::{Arbitrary, Unstructured};
17906 let mut buf = [0u8; 1024];
17907 rng.fill_bytes(&mut buf);
17908 let mut unstructured = Unstructured::new(&buf);
17909 Self::arbitrary(&mut unstructured).unwrap_or_default()
17910 }
17911}
17912impl Default for MAG_CAL_REPORT_DATA {
17913 fn default() -> Self {
17914 Self::DEFAULT.clone()
17915 }
17916}
17917impl MessageData for MAG_CAL_REPORT_DATA {
17918 type Message = MavMessage;
17919 const ID: u32 = 192u32;
17920 const NAME: &'static str = "MAG_CAL_REPORT";
17921 const EXTRA_CRC: u8 = 36u8;
17922 const ENCODED_LEN: usize = 54usize;
17923 fn deser(
17924 _version: MavlinkVersion,
17925 __input: &[u8],
17926 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17927 let avail_len = __input.len();
17928 let mut payload_buf = [0; Self::ENCODED_LEN];
17929 let mut buf = if avail_len < Self::ENCODED_LEN {
17930 payload_buf[0..avail_len].copy_from_slice(__input);
17931 Bytes::new(&payload_buf)
17932 } else {
17933 Bytes::new(__input)
17934 };
17935 let mut __struct = Self::default();
17936 __struct.fitness = buf.get_f32_le();
17937 __struct.ofs_x = buf.get_f32_le();
17938 __struct.ofs_y = buf.get_f32_le();
17939 __struct.ofs_z = buf.get_f32_le();
17940 __struct.diag_x = buf.get_f32_le();
17941 __struct.diag_y = buf.get_f32_le();
17942 __struct.diag_z = buf.get_f32_le();
17943 __struct.offdiag_x = buf.get_f32_le();
17944 __struct.offdiag_y = buf.get_f32_le();
17945 __struct.offdiag_z = buf.get_f32_le();
17946 __struct.compass_id = buf.get_u8();
17947 __struct.cal_mask = buf.get_u8();
17948 let tmp = buf.get_u8();
17949 __struct.cal_status =
17950 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17951 enum_type: "MagCalStatus",
17952 value: tmp as u32,
17953 })?;
17954 __struct.autosaved = buf.get_u8();
17955 __struct.orientation_confidence = buf.get_f32_le();
17956 let tmp = buf.get_u8();
17957 __struct.old_orientation =
17958 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17959 enum_type: "MavSensorOrientation",
17960 value: tmp as u32,
17961 })?;
17962 let tmp = buf.get_u8();
17963 __struct.new_orientation =
17964 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17965 enum_type: "MavSensorOrientation",
17966 value: tmp as u32,
17967 })?;
17968 __struct.scale_factor = buf.get_f32_le();
17969 Ok(__struct)
17970 }
17971 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17972 let mut __tmp = BytesMut::new(bytes);
17973 #[allow(clippy::absurd_extreme_comparisons)]
17974 #[allow(unused_comparisons)]
17975 if __tmp.remaining() < Self::ENCODED_LEN {
17976 panic!(
17977 "buffer is too small (need {} bytes, but got {})",
17978 Self::ENCODED_LEN,
17979 __tmp.remaining(),
17980 )
17981 }
17982 __tmp.put_f32_le(self.fitness);
17983 __tmp.put_f32_le(self.ofs_x);
17984 __tmp.put_f32_le(self.ofs_y);
17985 __tmp.put_f32_le(self.ofs_z);
17986 __tmp.put_f32_le(self.diag_x);
17987 __tmp.put_f32_le(self.diag_y);
17988 __tmp.put_f32_le(self.diag_z);
17989 __tmp.put_f32_le(self.offdiag_x);
17990 __tmp.put_f32_le(self.offdiag_y);
17991 __tmp.put_f32_le(self.offdiag_z);
17992 __tmp.put_u8(self.compass_id);
17993 __tmp.put_u8(self.cal_mask);
17994 __tmp.put_u8(self.cal_status as u8);
17995 __tmp.put_u8(self.autosaved);
17996 __tmp.put_f32_le(self.orientation_confidence);
17997 __tmp.put_u8(self.old_orientation as u8);
17998 __tmp.put_u8(self.new_orientation as u8);
17999 __tmp.put_f32_le(self.scale_factor);
18000 if matches!(version, MavlinkVersion::V2) {
18001 let len = __tmp.len();
18002 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18003 } else {
18004 __tmp.len()
18005 }
18006 }
18007}
18008#[doc = "id: 244"]
18009#[doc = "The interval between messages for a particular MAVLink message ID. This message is sent in response to the MAV_CMD_REQUEST_MESSAGE command with param1=244 (this message) and param2=message_id (the id of the message for which the interval is required). \tIt may also be sent in response to MAV_CMD_GET_MESSAGE_INTERVAL. \tThis interface replaces DATA_STREAM."]
18010#[derive(Debug, Clone, PartialEq)]
18011#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18012#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18013pub struct MESSAGE_INTERVAL_DATA {
18014 #[doc = "0 indicates the interval at which it is sent."]
18015 pub interval_us: i32,
18016 #[doc = "The ID of the requested MAVLink message. v1.0 is limited to 254 messages."]
18017 pub message_id: u16,
18018}
18019impl MESSAGE_INTERVAL_DATA {
18020 pub const ENCODED_LEN: usize = 6usize;
18021 pub const DEFAULT: Self = Self {
18022 interval_us: 0_i32,
18023 message_id: 0_u16,
18024 };
18025 #[cfg(feature = "arbitrary")]
18026 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18027 use arbitrary::{Arbitrary, Unstructured};
18028 let mut buf = [0u8; 1024];
18029 rng.fill_bytes(&mut buf);
18030 let mut unstructured = Unstructured::new(&buf);
18031 Self::arbitrary(&mut unstructured).unwrap_or_default()
18032 }
18033}
18034impl Default for MESSAGE_INTERVAL_DATA {
18035 fn default() -> Self {
18036 Self::DEFAULT.clone()
18037 }
18038}
18039impl MessageData for MESSAGE_INTERVAL_DATA {
18040 type Message = MavMessage;
18041 const ID: u32 = 244u32;
18042 const NAME: &'static str = "MESSAGE_INTERVAL";
18043 const EXTRA_CRC: u8 = 95u8;
18044 const ENCODED_LEN: usize = 6usize;
18045 fn deser(
18046 _version: MavlinkVersion,
18047 __input: &[u8],
18048 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18049 let avail_len = __input.len();
18050 let mut payload_buf = [0; Self::ENCODED_LEN];
18051 let mut buf = if avail_len < Self::ENCODED_LEN {
18052 payload_buf[0..avail_len].copy_from_slice(__input);
18053 Bytes::new(&payload_buf)
18054 } else {
18055 Bytes::new(__input)
18056 };
18057 let mut __struct = Self::default();
18058 __struct.interval_us = buf.get_i32_le();
18059 __struct.message_id = buf.get_u16_le();
18060 Ok(__struct)
18061 }
18062 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18063 let mut __tmp = BytesMut::new(bytes);
18064 #[allow(clippy::absurd_extreme_comparisons)]
18065 #[allow(unused_comparisons)]
18066 if __tmp.remaining() < Self::ENCODED_LEN {
18067 panic!(
18068 "buffer is too small (need {} bytes, but got {})",
18069 Self::ENCODED_LEN,
18070 __tmp.remaining(),
18071 )
18072 }
18073 __tmp.put_i32_le(self.interval_us);
18074 __tmp.put_u16_le(self.message_id);
18075 if matches!(version, MavlinkVersion::V2) {
18076 let len = __tmp.len();
18077 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18078 } else {
18079 __tmp.len()
18080 }
18081 }
18082}
18083#[doc = "id: 50"]
18084#[doc = "Bind a RC channel to a parameter. The parameter should change according to the RC channel value."]
18085#[derive(Debug, Clone, PartialEq)]
18086#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18087#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18088pub struct PARAM_MAP_RC_DATA {
18089 #[doc = "Initial parameter value"]
18090 pub param_value0: f32,
18091 #[doc = "Scale, maps the RC range [-1, 1] to a parameter value"]
18092 pub scale: f32,
18093 #[doc = "Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)"]
18094 pub param_value_min: f32,
18095 #[doc = "Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)"]
18096 pub param_value_max: f32,
18097 #[doc = "Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index."]
18098 pub param_index: i16,
18099 #[doc = "System ID"]
18100 pub target_system: u8,
18101 #[doc = "Component ID"]
18102 pub target_component: u8,
18103 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
18104 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18105 pub param_id: [u8; 16],
18106 #[doc = "Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC."]
18107 pub parameter_rc_channel_index: u8,
18108}
18109impl PARAM_MAP_RC_DATA {
18110 pub const ENCODED_LEN: usize = 37usize;
18111 pub const DEFAULT: Self = Self {
18112 param_value0: 0.0_f32,
18113 scale: 0.0_f32,
18114 param_value_min: 0.0_f32,
18115 param_value_max: 0.0_f32,
18116 param_index: 0_i16,
18117 target_system: 0_u8,
18118 target_component: 0_u8,
18119 param_id: [0_u8; 16usize],
18120 parameter_rc_channel_index: 0_u8,
18121 };
18122 #[cfg(feature = "arbitrary")]
18123 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18124 use arbitrary::{Arbitrary, Unstructured};
18125 let mut buf = [0u8; 1024];
18126 rng.fill_bytes(&mut buf);
18127 let mut unstructured = Unstructured::new(&buf);
18128 Self::arbitrary(&mut unstructured).unwrap_or_default()
18129 }
18130}
18131impl Default for PARAM_MAP_RC_DATA {
18132 fn default() -> Self {
18133 Self::DEFAULT.clone()
18134 }
18135}
18136impl MessageData for PARAM_MAP_RC_DATA {
18137 type Message = MavMessage;
18138 const ID: u32 = 50u32;
18139 const NAME: &'static str = "PARAM_MAP_RC";
18140 const EXTRA_CRC: u8 = 78u8;
18141 const ENCODED_LEN: usize = 37usize;
18142 fn deser(
18143 _version: MavlinkVersion,
18144 __input: &[u8],
18145 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18146 let avail_len = __input.len();
18147 let mut payload_buf = [0; Self::ENCODED_LEN];
18148 let mut buf = if avail_len < Self::ENCODED_LEN {
18149 payload_buf[0..avail_len].copy_from_slice(__input);
18150 Bytes::new(&payload_buf)
18151 } else {
18152 Bytes::new(__input)
18153 };
18154 let mut __struct = Self::default();
18155 __struct.param_value0 = buf.get_f32_le();
18156 __struct.scale = buf.get_f32_le();
18157 __struct.param_value_min = buf.get_f32_le();
18158 __struct.param_value_max = buf.get_f32_le();
18159 __struct.param_index = buf.get_i16_le();
18160 __struct.target_system = buf.get_u8();
18161 __struct.target_component = buf.get_u8();
18162 for v in &mut __struct.param_id {
18163 let val = buf.get_u8();
18164 *v = val;
18165 }
18166 __struct.parameter_rc_channel_index = buf.get_u8();
18167 Ok(__struct)
18168 }
18169 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18170 let mut __tmp = BytesMut::new(bytes);
18171 #[allow(clippy::absurd_extreme_comparisons)]
18172 #[allow(unused_comparisons)]
18173 if __tmp.remaining() < Self::ENCODED_LEN {
18174 panic!(
18175 "buffer is too small (need {} bytes, but got {})",
18176 Self::ENCODED_LEN,
18177 __tmp.remaining(),
18178 )
18179 }
18180 __tmp.put_f32_le(self.param_value0);
18181 __tmp.put_f32_le(self.scale);
18182 __tmp.put_f32_le(self.param_value_min);
18183 __tmp.put_f32_le(self.param_value_max);
18184 __tmp.put_i16_le(self.param_index);
18185 __tmp.put_u8(self.target_system);
18186 __tmp.put_u8(self.target_component);
18187 for val in &self.param_id {
18188 __tmp.put_u8(*val);
18189 }
18190 __tmp.put_u8(self.parameter_rc_channel_index);
18191 if matches!(version, MavlinkVersion::V2) {
18192 let len = __tmp.len();
18193 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18194 } else {
18195 __tmp.len()
18196 }
18197 }
18198}
18199#[doc = "id: 253"]
18200#[doc = "Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz)."]
18201#[derive(Debug, Clone, PartialEq)]
18202#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18203#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18204pub struct STATUSTEXT_DATA {
18205 #[doc = "Severity of status. Relies on the definitions within RFC-5424."]
18206 pub severity: MavSeverity,
18207 #[doc = "Status text message, without null termination character"]
18208 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18209 pub text: [u8; 50],
18210 #[doc = "Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately."]
18211 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18212 pub id: u16,
18213 #[doc = "This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk."]
18214 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18215 pub chunk_seq: u8,
18216}
18217impl STATUSTEXT_DATA {
18218 pub const ENCODED_LEN: usize = 54usize;
18219 pub const DEFAULT: Self = Self {
18220 severity: MavSeverity::DEFAULT,
18221 text: [0_u8; 50usize],
18222 id: 0_u16,
18223 chunk_seq: 0_u8,
18224 };
18225 #[cfg(feature = "arbitrary")]
18226 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18227 use arbitrary::{Arbitrary, Unstructured};
18228 let mut buf = [0u8; 1024];
18229 rng.fill_bytes(&mut buf);
18230 let mut unstructured = Unstructured::new(&buf);
18231 Self::arbitrary(&mut unstructured).unwrap_or_default()
18232 }
18233}
18234impl Default for STATUSTEXT_DATA {
18235 fn default() -> Self {
18236 Self::DEFAULT.clone()
18237 }
18238}
18239impl MessageData for STATUSTEXT_DATA {
18240 type Message = MavMessage;
18241 const ID: u32 = 253u32;
18242 const NAME: &'static str = "STATUSTEXT";
18243 const EXTRA_CRC: u8 = 83u8;
18244 const ENCODED_LEN: usize = 54usize;
18245 fn deser(
18246 _version: MavlinkVersion,
18247 __input: &[u8],
18248 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18249 let avail_len = __input.len();
18250 let mut payload_buf = [0; Self::ENCODED_LEN];
18251 let mut buf = if avail_len < Self::ENCODED_LEN {
18252 payload_buf[0..avail_len].copy_from_slice(__input);
18253 Bytes::new(&payload_buf)
18254 } else {
18255 Bytes::new(__input)
18256 };
18257 let mut __struct = Self::default();
18258 let tmp = buf.get_u8();
18259 __struct.severity =
18260 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18261 enum_type: "MavSeverity",
18262 value: tmp as u32,
18263 })?;
18264 for v in &mut __struct.text {
18265 let val = buf.get_u8();
18266 *v = val;
18267 }
18268 __struct.id = buf.get_u16_le();
18269 __struct.chunk_seq = buf.get_u8();
18270 Ok(__struct)
18271 }
18272 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18273 let mut __tmp = BytesMut::new(bytes);
18274 #[allow(clippy::absurd_extreme_comparisons)]
18275 #[allow(unused_comparisons)]
18276 if __tmp.remaining() < Self::ENCODED_LEN {
18277 panic!(
18278 "buffer is too small (need {} bytes, but got {})",
18279 Self::ENCODED_LEN,
18280 __tmp.remaining(),
18281 )
18282 }
18283 __tmp.put_u8(self.severity as u8);
18284 for val in &self.text {
18285 __tmp.put_u8(*val);
18286 }
18287 __tmp.put_u16_le(self.id);
18288 __tmp.put_u8(self.chunk_seq);
18289 if matches!(version, MavlinkVersion::V2) {
18290 let len = __tmp.len();
18291 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18292 } else {
18293 __tmp.len()
18294 }
18295 }
18296}
18297#[doc = "id: 276"]
18298#[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval."]
18299#[derive(Debug, Clone, PartialEq)]
18300#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18301#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18302pub struct CAMERA_TRACKING_GEO_STATUS_DATA {
18303 #[doc = "Latitude of tracked object"]
18304 pub lat: i32,
18305 #[doc = "Longitude of tracked object"]
18306 pub lon: i32,
18307 #[doc = "Altitude of tracked object(AMSL, WGS84)"]
18308 pub alt: f32,
18309 #[doc = "Horizontal accuracy. NAN if unknown"]
18310 pub h_acc: f32,
18311 #[doc = "Vertical accuracy. NAN if unknown"]
18312 pub v_acc: f32,
18313 #[doc = "North velocity of tracked object. NAN if unknown"]
18314 pub vel_n: f32,
18315 #[doc = "East velocity of tracked object. NAN if unknown"]
18316 pub vel_e: f32,
18317 #[doc = "Down velocity of tracked object. NAN if unknown"]
18318 pub vel_d: f32,
18319 #[doc = "Velocity accuracy. NAN if unknown"]
18320 pub vel_acc: f32,
18321 #[doc = "Distance between camera and tracked object. NAN if unknown"]
18322 pub dist: f32,
18323 #[doc = "Heading in radians, in NED. NAN if unknown"]
18324 pub hdg: f32,
18325 #[doc = "Accuracy of heading, in NED. NAN if unknown"]
18326 pub hdg_acc: f32,
18327 #[doc = "Current tracking status"]
18328 pub tracking_status: CameraTrackingStatusFlags,
18329 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
18330 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18331 pub camera_device_id: u8,
18332}
18333impl CAMERA_TRACKING_GEO_STATUS_DATA {
18334 pub const ENCODED_LEN: usize = 50usize;
18335 pub const DEFAULT: Self = Self {
18336 lat: 0_i32,
18337 lon: 0_i32,
18338 alt: 0.0_f32,
18339 h_acc: 0.0_f32,
18340 v_acc: 0.0_f32,
18341 vel_n: 0.0_f32,
18342 vel_e: 0.0_f32,
18343 vel_d: 0.0_f32,
18344 vel_acc: 0.0_f32,
18345 dist: 0.0_f32,
18346 hdg: 0.0_f32,
18347 hdg_acc: 0.0_f32,
18348 tracking_status: CameraTrackingStatusFlags::DEFAULT,
18349 camera_device_id: 0_u8,
18350 };
18351 #[cfg(feature = "arbitrary")]
18352 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18353 use arbitrary::{Arbitrary, Unstructured};
18354 let mut buf = [0u8; 1024];
18355 rng.fill_bytes(&mut buf);
18356 let mut unstructured = Unstructured::new(&buf);
18357 Self::arbitrary(&mut unstructured).unwrap_or_default()
18358 }
18359}
18360impl Default for CAMERA_TRACKING_GEO_STATUS_DATA {
18361 fn default() -> Self {
18362 Self::DEFAULT.clone()
18363 }
18364}
18365impl MessageData for CAMERA_TRACKING_GEO_STATUS_DATA {
18366 type Message = MavMessage;
18367 const ID: u32 = 276u32;
18368 const NAME: &'static str = "CAMERA_TRACKING_GEO_STATUS";
18369 const EXTRA_CRC: u8 = 18u8;
18370 const ENCODED_LEN: usize = 50usize;
18371 fn deser(
18372 _version: MavlinkVersion,
18373 __input: &[u8],
18374 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18375 let avail_len = __input.len();
18376 let mut payload_buf = [0; Self::ENCODED_LEN];
18377 let mut buf = if avail_len < Self::ENCODED_LEN {
18378 payload_buf[0..avail_len].copy_from_slice(__input);
18379 Bytes::new(&payload_buf)
18380 } else {
18381 Bytes::new(__input)
18382 };
18383 let mut __struct = Self::default();
18384 __struct.lat = buf.get_i32_le();
18385 __struct.lon = buf.get_i32_le();
18386 __struct.alt = buf.get_f32_le();
18387 __struct.h_acc = buf.get_f32_le();
18388 __struct.v_acc = buf.get_f32_le();
18389 __struct.vel_n = buf.get_f32_le();
18390 __struct.vel_e = buf.get_f32_le();
18391 __struct.vel_d = buf.get_f32_le();
18392 __struct.vel_acc = buf.get_f32_le();
18393 __struct.dist = buf.get_f32_le();
18394 __struct.hdg = buf.get_f32_le();
18395 __struct.hdg_acc = buf.get_f32_le();
18396 let tmp = buf.get_u8();
18397 __struct.tracking_status =
18398 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18399 enum_type: "CameraTrackingStatusFlags",
18400 value: tmp as u32,
18401 })?;
18402 __struct.camera_device_id = buf.get_u8();
18403 Ok(__struct)
18404 }
18405 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18406 let mut __tmp = BytesMut::new(bytes);
18407 #[allow(clippy::absurd_extreme_comparisons)]
18408 #[allow(unused_comparisons)]
18409 if __tmp.remaining() < Self::ENCODED_LEN {
18410 panic!(
18411 "buffer is too small (need {} bytes, but got {})",
18412 Self::ENCODED_LEN,
18413 __tmp.remaining(),
18414 )
18415 }
18416 __tmp.put_i32_le(self.lat);
18417 __tmp.put_i32_le(self.lon);
18418 __tmp.put_f32_le(self.alt);
18419 __tmp.put_f32_le(self.h_acc);
18420 __tmp.put_f32_le(self.v_acc);
18421 __tmp.put_f32_le(self.vel_n);
18422 __tmp.put_f32_le(self.vel_e);
18423 __tmp.put_f32_le(self.vel_d);
18424 __tmp.put_f32_le(self.vel_acc);
18425 __tmp.put_f32_le(self.dist);
18426 __tmp.put_f32_le(self.hdg);
18427 __tmp.put_f32_le(self.hdg_acc);
18428 __tmp.put_u8(self.tracking_status as u8);
18429 __tmp.put_u8(self.camera_device_id);
18430 if matches!(version, MavlinkVersion::V2) {
18431 let len = __tmp.len();
18432 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18433 } else {
18434 __tmp.len()
18435 }
18436 }
18437}
18438#[doc = "id: 123"]
18439#[doc = "Data for injecting into the onboard GPS (used for DGPS)."]
18440#[derive(Debug, Clone, PartialEq)]
18441#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18442#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18443pub struct GPS_INJECT_DATA_DATA {
18444 #[doc = "System ID"]
18445 pub target_system: u8,
18446 #[doc = "Component ID"]
18447 pub target_component: u8,
18448 #[doc = "Data length"]
18449 pub len: u8,
18450 #[doc = "Raw data (110 is enough for 12 satellites of RTCMv2)"]
18451 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18452 pub data: [u8; 110],
18453}
18454impl GPS_INJECT_DATA_DATA {
18455 pub const ENCODED_LEN: usize = 113usize;
18456 pub const DEFAULT: Self = Self {
18457 target_system: 0_u8,
18458 target_component: 0_u8,
18459 len: 0_u8,
18460 data: [0_u8; 110usize],
18461 };
18462 #[cfg(feature = "arbitrary")]
18463 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18464 use arbitrary::{Arbitrary, Unstructured};
18465 let mut buf = [0u8; 1024];
18466 rng.fill_bytes(&mut buf);
18467 let mut unstructured = Unstructured::new(&buf);
18468 Self::arbitrary(&mut unstructured).unwrap_or_default()
18469 }
18470}
18471impl Default for GPS_INJECT_DATA_DATA {
18472 fn default() -> Self {
18473 Self::DEFAULT.clone()
18474 }
18475}
18476impl MessageData for GPS_INJECT_DATA_DATA {
18477 type Message = MavMessage;
18478 const ID: u32 = 123u32;
18479 const NAME: &'static str = "GPS_INJECT_DATA";
18480 const EXTRA_CRC: u8 = 250u8;
18481 const ENCODED_LEN: usize = 113usize;
18482 fn deser(
18483 _version: MavlinkVersion,
18484 __input: &[u8],
18485 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18486 let avail_len = __input.len();
18487 let mut payload_buf = [0; Self::ENCODED_LEN];
18488 let mut buf = if avail_len < Self::ENCODED_LEN {
18489 payload_buf[0..avail_len].copy_from_slice(__input);
18490 Bytes::new(&payload_buf)
18491 } else {
18492 Bytes::new(__input)
18493 };
18494 let mut __struct = Self::default();
18495 __struct.target_system = buf.get_u8();
18496 __struct.target_component = buf.get_u8();
18497 __struct.len = buf.get_u8();
18498 for v in &mut __struct.data {
18499 let val = buf.get_u8();
18500 *v = val;
18501 }
18502 Ok(__struct)
18503 }
18504 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18505 let mut __tmp = BytesMut::new(bytes);
18506 #[allow(clippy::absurd_extreme_comparisons)]
18507 #[allow(unused_comparisons)]
18508 if __tmp.remaining() < Self::ENCODED_LEN {
18509 panic!(
18510 "buffer is too small (need {} bytes, but got {})",
18511 Self::ENCODED_LEN,
18512 __tmp.remaining(),
18513 )
18514 }
18515 __tmp.put_u8(self.target_system);
18516 __tmp.put_u8(self.target_component);
18517 __tmp.put_u8(self.len);
18518 for val in &self.data {
18519 __tmp.put_u8(*val);
18520 }
18521 if matches!(version, MavlinkVersion::V2) {
18522 let len = __tmp.len();
18523 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18524 } else {
18525 __tmp.len()
18526 }
18527 }
18528}
18529#[doc = "id: 74"]
18530#[doc = "Metrics typically displayed on a HUD for fixed wing aircraft."]
18531#[derive(Debug, Clone, PartialEq)]
18532#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18533#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18534pub struct VFR_HUD_DATA {
18535 #[doc = "Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed."]
18536 pub airspeed: f32,
18537 #[doc = "Current ground speed."]
18538 pub groundspeed: f32,
18539 #[doc = "Current altitude (MSL)."]
18540 pub alt: f32,
18541 #[doc = "Current climb rate."]
18542 pub climb: f32,
18543 #[doc = "Current heading in compass units (0-360, 0=north)."]
18544 pub heading: i16,
18545 #[doc = "Current throttle setting (0 to 100)."]
18546 pub throttle: u16,
18547}
18548impl VFR_HUD_DATA {
18549 pub const ENCODED_LEN: usize = 20usize;
18550 pub const DEFAULT: Self = Self {
18551 airspeed: 0.0_f32,
18552 groundspeed: 0.0_f32,
18553 alt: 0.0_f32,
18554 climb: 0.0_f32,
18555 heading: 0_i16,
18556 throttle: 0_u16,
18557 };
18558 #[cfg(feature = "arbitrary")]
18559 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18560 use arbitrary::{Arbitrary, Unstructured};
18561 let mut buf = [0u8; 1024];
18562 rng.fill_bytes(&mut buf);
18563 let mut unstructured = Unstructured::new(&buf);
18564 Self::arbitrary(&mut unstructured).unwrap_or_default()
18565 }
18566}
18567impl Default for VFR_HUD_DATA {
18568 fn default() -> Self {
18569 Self::DEFAULT.clone()
18570 }
18571}
18572impl MessageData for VFR_HUD_DATA {
18573 type Message = MavMessage;
18574 const ID: u32 = 74u32;
18575 const NAME: &'static str = "VFR_HUD";
18576 const EXTRA_CRC: u8 = 20u8;
18577 const ENCODED_LEN: usize = 20usize;
18578 fn deser(
18579 _version: MavlinkVersion,
18580 __input: &[u8],
18581 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18582 let avail_len = __input.len();
18583 let mut payload_buf = [0; Self::ENCODED_LEN];
18584 let mut buf = if avail_len < Self::ENCODED_LEN {
18585 payload_buf[0..avail_len].copy_from_slice(__input);
18586 Bytes::new(&payload_buf)
18587 } else {
18588 Bytes::new(__input)
18589 };
18590 let mut __struct = Self::default();
18591 __struct.airspeed = buf.get_f32_le();
18592 __struct.groundspeed = buf.get_f32_le();
18593 __struct.alt = buf.get_f32_le();
18594 __struct.climb = buf.get_f32_le();
18595 __struct.heading = buf.get_i16_le();
18596 __struct.throttle = buf.get_u16_le();
18597 Ok(__struct)
18598 }
18599 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18600 let mut __tmp = BytesMut::new(bytes);
18601 #[allow(clippy::absurd_extreme_comparisons)]
18602 #[allow(unused_comparisons)]
18603 if __tmp.remaining() < Self::ENCODED_LEN {
18604 panic!(
18605 "buffer is too small (need {} bytes, but got {})",
18606 Self::ENCODED_LEN,
18607 __tmp.remaining(),
18608 )
18609 }
18610 __tmp.put_f32_le(self.airspeed);
18611 __tmp.put_f32_le(self.groundspeed);
18612 __tmp.put_f32_le(self.alt);
18613 __tmp.put_f32_le(self.climb);
18614 __tmp.put_i16_le(self.heading);
18615 __tmp.put_u16_le(self.throttle);
18616 if matches!(version, MavlinkVersion::V2) {
18617 let len = __tmp.len();
18618 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18619 } else {
18620 __tmp.len()
18621 }
18622 }
18623}
18624#[doc = "id: 73"]
18625#[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). See also <https://mavlink.io/en/services/mission.html>."]
18626#[derive(Debug, Clone, PartialEq)]
18627#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18628#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18629pub struct MISSION_ITEM_INT_DATA {
18630 #[doc = "PARAM1, see MAV_CMD enum"]
18631 pub param1: f32,
18632 #[doc = "PARAM2, see MAV_CMD enum"]
18633 pub param2: f32,
18634 #[doc = "PARAM3, see MAV_CMD enum"]
18635 pub param3: f32,
18636 #[doc = "PARAM4, see MAV_CMD enum"]
18637 pub param4: f32,
18638 #[doc = "PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7"]
18639 pub x: i32,
18640 #[doc = "PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7"]
18641 pub y: i32,
18642 #[doc = "PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame."]
18643 pub z: f32,
18644 #[doc = "Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4)."]
18645 pub seq: u16,
18646 #[doc = "The scheduled action for the waypoint."]
18647 pub command: MavCmd,
18648 #[doc = "System ID"]
18649 pub target_system: u8,
18650 #[doc = "Component ID"]
18651 pub target_component: u8,
18652 #[doc = "The coordinate system of the waypoint."]
18653 pub frame: MavFrame,
18654 #[doc = "false:0, true:1"]
18655 pub current: u8,
18656 #[doc = "Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes."]
18657 pub autocontinue: u8,
18658 #[doc = "Mission type."]
18659 #[cfg_attr(feature = "serde", serde(default))]
18660 pub mission_type: MavMissionType,
18661}
18662impl MISSION_ITEM_INT_DATA {
18663 pub const ENCODED_LEN: usize = 38usize;
18664 pub const DEFAULT: Self = Self {
18665 param1: 0.0_f32,
18666 param2: 0.0_f32,
18667 param3: 0.0_f32,
18668 param4: 0.0_f32,
18669 x: 0_i32,
18670 y: 0_i32,
18671 z: 0.0_f32,
18672 seq: 0_u16,
18673 command: MavCmd::DEFAULT,
18674 target_system: 0_u8,
18675 target_component: 0_u8,
18676 frame: MavFrame::DEFAULT,
18677 current: 0_u8,
18678 autocontinue: 0_u8,
18679 mission_type: MavMissionType::DEFAULT,
18680 };
18681 #[cfg(feature = "arbitrary")]
18682 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18683 use arbitrary::{Arbitrary, Unstructured};
18684 let mut buf = [0u8; 1024];
18685 rng.fill_bytes(&mut buf);
18686 let mut unstructured = Unstructured::new(&buf);
18687 Self::arbitrary(&mut unstructured).unwrap_or_default()
18688 }
18689}
18690impl Default for MISSION_ITEM_INT_DATA {
18691 fn default() -> Self {
18692 Self::DEFAULT.clone()
18693 }
18694}
18695impl MessageData for MISSION_ITEM_INT_DATA {
18696 type Message = MavMessage;
18697 const ID: u32 = 73u32;
18698 const NAME: &'static str = "MISSION_ITEM_INT";
18699 const EXTRA_CRC: u8 = 38u8;
18700 const ENCODED_LEN: usize = 38usize;
18701 fn deser(
18702 _version: MavlinkVersion,
18703 __input: &[u8],
18704 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18705 let avail_len = __input.len();
18706 let mut payload_buf = [0; Self::ENCODED_LEN];
18707 let mut buf = if avail_len < Self::ENCODED_LEN {
18708 payload_buf[0..avail_len].copy_from_slice(__input);
18709 Bytes::new(&payload_buf)
18710 } else {
18711 Bytes::new(__input)
18712 };
18713 let mut __struct = Self::default();
18714 __struct.param1 = buf.get_f32_le();
18715 __struct.param2 = buf.get_f32_le();
18716 __struct.param3 = buf.get_f32_le();
18717 __struct.param4 = buf.get_f32_le();
18718 __struct.x = buf.get_i32_le();
18719 __struct.y = buf.get_i32_le();
18720 __struct.z = buf.get_f32_le();
18721 __struct.seq = buf.get_u16_le();
18722 let tmp = buf.get_u16_le();
18723 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
18724 ::mavlink_core::error::ParserError::InvalidEnum {
18725 enum_type: "MavCmd",
18726 value: tmp as u32,
18727 },
18728 )?;
18729 __struct.target_system = buf.get_u8();
18730 __struct.target_component = buf.get_u8();
18731 let tmp = buf.get_u8();
18732 __struct.frame =
18733 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18734 enum_type: "MavFrame",
18735 value: tmp as u32,
18736 })?;
18737 __struct.current = buf.get_u8();
18738 __struct.autocontinue = buf.get_u8();
18739 let tmp = buf.get_u8();
18740 __struct.mission_type =
18741 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18742 enum_type: "MavMissionType",
18743 value: tmp as u32,
18744 })?;
18745 Ok(__struct)
18746 }
18747 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18748 let mut __tmp = BytesMut::new(bytes);
18749 #[allow(clippy::absurd_extreme_comparisons)]
18750 #[allow(unused_comparisons)]
18751 if __tmp.remaining() < Self::ENCODED_LEN {
18752 panic!(
18753 "buffer is too small (need {} bytes, but got {})",
18754 Self::ENCODED_LEN,
18755 __tmp.remaining(),
18756 )
18757 }
18758 __tmp.put_f32_le(self.param1);
18759 __tmp.put_f32_le(self.param2);
18760 __tmp.put_f32_le(self.param3);
18761 __tmp.put_f32_le(self.param4);
18762 __tmp.put_i32_le(self.x);
18763 __tmp.put_i32_le(self.y);
18764 __tmp.put_f32_le(self.z);
18765 __tmp.put_u16_le(self.seq);
18766 __tmp.put_u16_le(self.command as u16);
18767 __tmp.put_u8(self.target_system);
18768 __tmp.put_u8(self.target_component);
18769 __tmp.put_u8(self.frame as u8);
18770 __tmp.put_u8(self.current);
18771 __tmp.put_u8(self.autocontinue);
18772 __tmp.put_u8(self.mission_type as u8);
18773 if matches!(version, MavlinkVersion::V2) {
18774 let len = __tmp.len();
18775 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18776 } else {
18777 __tmp.len()
18778 }
18779 }
18780}
18781#[doc = "id: 335"]
18782#[doc = "Status of the Iridium SBD link."]
18783#[derive(Debug, Clone, PartialEq)]
18784#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18785#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18786pub struct ISBD_LINK_STATUS_DATA {
18787 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
18788 pub timestamp: u64,
18789 #[doc = "Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
18790 pub last_heartbeat: u64,
18791 #[doc = "Number of failed SBD sessions."]
18792 pub failed_sessions: u16,
18793 #[doc = "Number of successful SBD sessions."]
18794 pub successful_sessions: u16,
18795 #[doc = "Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength."]
18796 pub signal_quality: u8,
18797 #[doc = "1: Ring call pending, 0: No call pending."]
18798 pub ring_pending: u8,
18799 #[doc = "1: Transmission session pending, 0: No transmission session pending."]
18800 pub tx_session_pending: u8,
18801 #[doc = "1: Receiving session pending, 0: No receiving session pending."]
18802 pub rx_session_pending: u8,
18803}
18804impl ISBD_LINK_STATUS_DATA {
18805 pub const ENCODED_LEN: usize = 24usize;
18806 pub const DEFAULT: Self = Self {
18807 timestamp: 0_u64,
18808 last_heartbeat: 0_u64,
18809 failed_sessions: 0_u16,
18810 successful_sessions: 0_u16,
18811 signal_quality: 0_u8,
18812 ring_pending: 0_u8,
18813 tx_session_pending: 0_u8,
18814 rx_session_pending: 0_u8,
18815 };
18816 #[cfg(feature = "arbitrary")]
18817 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18818 use arbitrary::{Arbitrary, Unstructured};
18819 let mut buf = [0u8; 1024];
18820 rng.fill_bytes(&mut buf);
18821 let mut unstructured = Unstructured::new(&buf);
18822 Self::arbitrary(&mut unstructured).unwrap_or_default()
18823 }
18824}
18825impl Default for ISBD_LINK_STATUS_DATA {
18826 fn default() -> Self {
18827 Self::DEFAULT.clone()
18828 }
18829}
18830impl MessageData for ISBD_LINK_STATUS_DATA {
18831 type Message = MavMessage;
18832 const ID: u32 = 335u32;
18833 const NAME: &'static str = "ISBD_LINK_STATUS";
18834 const EXTRA_CRC: u8 = 225u8;
18835 const ENCODED_LEN: usize = 24usize;
18836 fn deser(
18837 _version: MavlinkVersion,
18838 __input: &[u8],
18839 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18840 let avail_len = __input.len();
18841 let mut payload_buf = [0; Self::ENCODED_LEN];
18842 let mut buf = if avail_len < Self::ENCODED_LEN {
18843 payload_buf[0..avail_len].copy_from_slice(__input);
18844 Bytes::new(&payload_buf)
18845 } else {
18846 Bytes::new(__input)
18847 };
18848 let mut __struct = Self::default();
18849 __struct.timestamp = buf.get_u64_le();
18850 __struct.last_heartbeat = buf.get_u64_le();
18851 __struct.failed_sessions = buf.get_u16_le();
18852 __struct.successful_sessions = buf.get_u16_le();
18853 __struct.signal_quality = buf.get_u8();
18854 __struct.ring_pending = buf.get_u8();
18855 __struct.tx_session_pending = buf.get_u8();
18856 __struct.rx_session_pending = buf.get_u8();
18857 Ok(__struct)
18858 }
18859 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18860 let mut __tmp = BytesMut::new(bytes);
18861 #[allow(clippy::absurd_extreme_comparisons)]
18862 #[allow(unused_comparisons)]
18863 if __tmp.remaining() < Self::ENCODED_LEN {
18864 panic!(
18865 "buffer is too small (need {} bytes, but got {})",
18866 Self::ENCODED_LEN,
18867 __tmp.remaining(),
18868 )
18869 }
18870 __tmp.put_u64_le(self.timestamp);
18871 __tmp.put_u64_le(self.last_heartbeat);
18872 __tmp.put_u16_le(self.failed_sessions);
18873 __tmp.put_u16_le(self.successful_sessions);
18874 __tmp.put_u8(self.signal_quality);
18875 __tmp.put_u8(self.ring_pending);
18876 __tmp.put_u8(self.tx_session_pending);
18877 __tmp.put_u8(self.rx_session_pending);
18878 if matches!(version, MavlinkVersion::V2) {
18879 let len = __tmp.len();
18880 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18881 } else {
18882 __tmp.len()
18883 }
18884 }
18885}
18886#[doc = "id: 400"]
18887#[doc = "Play vehicle tone/tune (buzzer). Supersedes message PLAY_TUNE."]
18888#[derive(Debug, Clone, PartialEq)]
18889#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18890#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18891pub struct PLAY_TUNE_V2_DATA {
18892 #[doc = "Tune format"]
18893 pub format: TuneFormat,
18894 #[doc = "System ID"]
18895 pub target_system: u8,
18896 #[doc = "Component ID"]
18897 pub target_component: u8,
18898 #[doc = "Tune definition as a NULL-terminated string."]
18899 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18900 pub tune: [u8; 248],
18901}
18902impl PLAY_TUNE_V2_DATA {
18903 pub const ENCODED_LEN: usize = 254usize;
18904 pub const DEFAULT: Self = Self {
18905 format: TuneFormat::DEFAULT,
18906 target_system: 0_u8,
18907 target_component: 0_u8,
18908 tune: [0_u8; 248usize],
18909 };
18910 #[cfg(feature = "arbitrary")]
18911 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18912 use arbitrary::{Arbitrary, Unstructured};
18913 let mut buf = [0u8; 1024];
18914 rng.fill_bytes(&mut buf);
18915 let mut unstructured = Unstructured::new(&buf);
18916 Self::arbitrary(&mut unstructured).unwrap_or_default()
18917 }
18918}
18919impl Default for PLAY_TUNE_V2_DATA {
18920 fn default() -> Self {
18921 Self::DEFAULT.clone()
18922 }
18923}
18924impl MessageData for PLAY_TUNE_V2_DATA {
18925 type Message = MavMessage;
18926 const ID: u32 = 400u32;
18927 const NAME: &'static str = "PLAY_TUNE_V2";
18928 const EXTRA_CRC: u8 = 110u8;
18929 const ENCODED_LEN: usize = 254usize;
18930 fn deser(
18931 _version: MavlinkVersion,
18932 __input: &[u8],
18933 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18934 let avail_len = __input.len();
18935 let mut payload_buf = [0; Self::ENCODED_LEN];
18936 let mut buf = if avail_len < Self::ENCODED_LEN {
18937 payload_buf[0..avail_len].copy_from_slice(__input);
18938 Bytes::new(&payload_buf)
18939 } else {
18940 Bytes::new(__input)
18941 };
18942 let mut __struct = Self::default();
18943 let tmp = buf.get_u32_le();
18944 __struct.format = FromPrimitive::from_u32(tmp).ok_or(
18945 ::mavlink_core::error::ParserError::InvalidEnum {
18946 enum_type: "TuneFormat",
18947 value: tmp as u32,
18948 },
18949 )?;
18950 __struct.target_system = buf.get_u8();
18951 __struct.target_component = buf.get_u8();
18952 for v in &mut __struct.tune {
18953 let val = buf.get_u8();
18954 *v = val;
18955 }
18956 Ok(__struct)
18957 }
18958 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18959 let mut __tmp = BytesMut::new(bytes);
18960 #[allow(clippy::absurd_extreme_comparisons)]
18961 #[allow(unused_comparisons)]
18962 if __tmp.remaining() < Self::ENCODED_LEN {
18963 panic!(
18964 "buffer is too small (need {} bytes, but got {})",
18965 Self::ENCODED_LEN,
18966 __tmp.remaining(),
18967 )
18968 }
18969 __tmp.put_u32_le(self.format as u32);
18970 __tmp.put_u8(self.target_system);
18971 __tmp.put_u8(self.target_component);
18972 for val in &self.tune {
18973 __tmp.put_u8(*val);
18974 }
18975 if matches!(version, MavlinkVersion::V2) {
18976 let len = __tmp.len();
18977 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18978 } else {
18979 __tmp.len()
18980 }
18981 }
18982}
18983#[doc = "id: 260"]
18984#[doc = "Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
18985#[derive(Debug, Clone, PartialEq)]
18986#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18987#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18988pub struct CAMERA_SETTINGS_DATA {
18989 #[doc = "Timestamp (time since system boot)."]
18990 pub time_boot_ms: u32,
18991 #[doc = "Camera mode"]
18992 pub mode_id: CameraMode,
18993 #[doc = "Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known)"]
18994 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18995 pub zoomLevel: f32,
18996 #[doc = "Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known)"]
18997 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18998 pub focusLevel: f32,
18999 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
19000 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19001 pub camera_device_id: u8,
19002}
19003impl CAMERA_SETTINGS_DATA {
19004 pub const ENCODED_LEN: usize = 14usize;
19005 pub const DEFAULT: Self = Self {
19006 time_boot_ms: 0_u32,
19007 mode_id: CameraMode::DEFAULT,
19008 zoomLevel: 0.0_f32,
19009 focusLevel: 0.0_f32,
19010 camera_device_id: 0_u8,
19011 };
19012 #[cfg(feature = "arbitrary")]
19013 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19014 use arbitrary::{Arbitrary, Unstructured};
19015 let mut buf = [0u8; 1024];
19016 rng.fill_bytes(&mut buf);
19017 let mut unstructured = Unstructured::new(&buf);
19018 Self::arbitrary(&mut unstructured).unwrap_or_default()
19019 }
19020}
19021impl Default for CAMERA_SETTINGS_DATA {
19022 fn default() -> Self {
19023 Self::DEFAULT.clone()
19024 }
19025}
19026impl MessageData for CAMERA_SETTINGS_DATA {
19027 type Message = MavMessage;
19028 const ID: u32 = 260u32;
19029 const NAME: &'static str = "CAMERA_SETTINGS";
19030 const EXTRA_CRC: u8 = 146u8;
19031 const ENCODED_LEN: usize = 14usize;
19032 fn deser(
19033 _version: MavlinkVersion,
19034 __input: &[u8],
19035 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19036 let avail_len = __input.len();
19037 let mut payload_buf = [0; Self::ENCODED_LEN];
19038 let mut buf = if avail_len < Self::ENCODED_LEN {
19039 payload_buf[0..avail_len].copy_from_slice(__input);
19040 Bytes::new(&payload_buf)
19041 } else {
19042 Bytes::new(__input)
19043 };
19044 let mut __struct = Self::default();
19045 __struct.time_boot_ms = buf.get_u32_le();
19046 let tmp = buf.get_u8();
19047 __struct.mode_id =
19048 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19049 enum_type: "CameraMode",
19050 value: tmp as u32,
19051 })?;
19052 __struct.zoomLevel = buf.get_f32_le();
19053 __struct.focusLevel = buf.get_f32_le();
19054 __struct.camera_device_id = buf.get_u8();
19055 Ok(__struct)
19056 }
19057 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19058 let mut __tmp = BytesMut::new(bytes);
19059 #[allow(clippy::absurd_extreme_comparisons)]
19060 #[allow(unused_comparisons)]
19061 if __tmp.remaining() < Self::ENCODED_LEN {
19062 panic!(
19063 "buffer is too small (need {} bytes, but got {})",
19064 Self::ENCODED_LEN,
19065 __tmp.remaining(),
19066 )
19067 }
19068 __tmp.put_u32_le(self.time_boot_ms);
19069 __tmp.put_u8(self.mode_id as u8);
19070 __tmp.put_f32_le(self.zoomLevel);
19071 __tmp.put_f32_le(self.focusLevel);
19072 __tmp.put_u8(self.camera_device_id);
19073 if matches!(version, MavlinkVersion::V2) {
19074 let len = __tmp.len();
19075 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19076 } else {
19077 __tmp.len()
19078 }
19079 }
19080}
19081#[doc = "id: 45"]
19082#[doc = "Delete all mission items at once."]
19083#[derive(Debug, Clone, PartialEq)]
19084#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19085#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19086pub struct MISSION_CLEAR_ALL_DATA {
19087 #[doc = "System ID"]
19088 pub target_system: u8,
19089 #[doc = "Component ID"]
19090 pub target_component: u8,
19091 #[doc = "Mission type."]
19092 #[cfg_attr(feature = "serde", serde(default))]
19093 pub mission_type: MavMissionType,
19094}
19095impl MISSION_CLEAR_ALL_DATA {
19096 pub const ENCODED_LEN: usize = 3usize;
19097 pub const DEFAULT: Self = Self {
19098 target_system: 0_u8,
19099 target_component: 0_u8,
19100 mission_type: MavMissionType::DEFAULT,
19101 };
19102 #[cfg(feature = "arbitrary")]
19103 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19104 use arbitrary::{Arbitrary, Unstructured};
19105 let mut buf = [0u8; 1024];
19106 rng.fill_bytes(&mut buf);
19107 let mut unstructured = Unstructured::new(&buf);
19108 Self::arbitrary(&mut unstructured).unwrap_or_default()
19109 }
19110}
19111impl Default for MISSION_CLEAR_ALL_DATA {
19112 fn default() -> Self {
19113 Self::DEFAULT.clone()
19114 }
19115}
19116impl MessageData for MISSION_CLEAR_ALL_DATA {
19117 type Message = MavMessage;
19118 const ID: u32 = 45u32;
19119 const NAME: &'static str = "MISSION_CLEAR_ALL";
19120 const EXTRA_CRC: u8 = 232u8;
19121 const ENCODED_LEN: usize = 3usize;
19122 fn deser(
19123 _version: MavlinkVersion,
19124 __input: &[u8],
19125 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19126 let avail_len = __input.len();
19127 let mut payload_buf = [0; Self::ENCODED_LEN];
19128 let mut buf = if avail_len < Self::ENCODED_LEN {
19129 payload_buf[0..avail_len].copy_from_slice(__input);
19130 Bytes::new(&payload_buf)
19131 } else {
19132 Bytes::new(__input)
19133 };
19134 let mut __struct = Self::default();
19135 __struct.target_system = buf.get_u8();
19136 __struct.target_component = buf.get_u8();
19137 let tmp = buf.get_u8();
19138 __struct.mission_type =
19139 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19140 enum_type: "MavMissionType",
19141 value: tmp as u32,
19142 })?;
19143 Ok(__struct)
19144 }
19145 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19146 let mut __tmp = BytesMut::new(bytes);
19147 #[allow(clippy::absurd_extreme_comparisons)]
19148 #[allow(unused_comparisons)]
19149 if __tmp.remaining() < Self::ENCODED_LEN {
19150 panic!(
19151 "buffer is too small (need {} bytes, but got {})",
19152 Self::ENCODED_LEN,
19153 __tmp.remaining(),
19154 )
19155 }
19156 __tmp.put_u8(self.target_system);
19157 __tmp.put_u8(self.target_component);
19158 __tmp.put_u8(self.mission_type as u8);
19159 if matches!(version, MavlinkVersion::V2) {
19160 let len = __tmp.len();
19161 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19162 } else {
19163 __tmp.len()
19164 }
19165 }
19166}
19167#[doc = "id: 81"]
19168#[doc = "Setpoint in roll, pitch, yaw and thrust from the operator."]
19169#[derive(Debug, Clone, PartialEq)]
19170#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19171#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19172pub struct MANUAL_SETPOINT_DATA {
19173 #[doc = "Timestamp (time since system boot)."]
19174 pub time_boot_ms: u32,
19175 #[doc = "Desired roll rate"]
19176 pub roll: f32,
19177 #[doc = "Desired pitch rate"]
19178 pub pitch: f32,
19179 #[doc = "Desired yaw rate"]
19180 pub yaw: f32,
19181 #[doc = "Collective thrust, normalized to 0 .. 1"]
19182 pub thrust: f32,
19183 #[doc = "Flight mode switch position, 0.. 255"]
19184 pub mode_switch: u8,
19185 #[doc = "Override mode switch position, 0.. 255"]
19186 pub manual_override_switch: u8,
19187}
19188impl MANUAL_SETPOINT_DATA {
19189 pub const ENCODED_LEN: usize = 22usize;
19190 pub const DEFAULT: Self = Self {
19191 time_boot_ms: 0_u32,
19192 roll: 0.0_f32,
19193 pitch: 0.0_f32,
19194 yaw: 0.0_f32,
19195 thrust: 0.0_f32,
19196 mode_switch: 0_u8,
19197 manual_override_switch: 0_u8,
19198 };
19199 #[cfg(feature = "arbitrary")]
19200 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19201 use arbitrary::{Arbitrary, Unstructured};
19202 let mut buf = [0u8; 1024];
19203 rng.fill_bytes(&mut buf);
19204 let mut unstructured = Unstructured::new(&buf);
19205 Self::arbitrary(&mut unstructured).unwrap_or_default()
19206 }
19207}
19208impl Default for MANUAL_SETPOINT_DATA {
19209 fn default() -> Self {
19210 Self::DEFAULT.clone()
19211 }
19212}
19213impl MessageData for MANUAL_SETPOINT_DATA {
19214 type Message = MavMessage;
19215 const ID: u32 = 81u32;
19216 const NAME: &'static str = "MANUAL_SETPOINT";
19217 const EXTRA_CRC: u8 = 106u8;
19218 const ENCODED_LEN: usize = 22usize;
19219 fn deser(
19220 _version: MavlinkVersion,
19221 __input: &[u8],
19222 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19223 let avail_len = __input.len();
19224 let mut payload_buf = [0; Self::ENCODED_LEN];
19225 let mut buf = if avail_len < Self::ENCODED_LEN {
19226 payload_buf[0..avail_len].copy_from_slice(__input);
19227 Bytes::new(&payload_buf)
19228 } else {
19229 Bytes::new(__input)
19230 };
19231 let mut __struct = Self::default();
19232 __struct.time_boot_ms = buf.get_u32_le();
19233 __struct.roll = buf.get_f32_le();
19234 __struct.pitch = buf.get_f32_le();
19235 __struct.yaw = buf.get_f32_le();
19236 __struct.thrust = buf.get_f32_le();
19237 __struct.mode_switch = buf.get_u8();
19238 __struct.manual_override_switch = buf.get_u8();
19239 Ok(__struct)
19240 }
19241 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19242 let mut __tmp = BytesMut::new(bytes);
19243 #[allow(clippy::absurd_extreme_comparisons)]
19244 #[allow(unused_comparisons)]
19245 if __tmp.remaining() < Self::ENCODED_LEN {
19246 panic!(
19247 "buffer is too small (need {} bytes, but got {})",
19248 Self::ENCODED_LEN,
19249 __tmp.remaining(),
19250 )
19251 }
19252 __tmp.put_u32_le(self.time_boot_ms);
19253 __tmp.put_f32_le(self.roll);
19254 __tmp.put_f32_le(self.pitch);
19255 __tmp.put_f32_le(self.yaw);
19256 __tmp.put_f32_le(self.thrust);
19257 __tmp.put_u8(self.mode_switch);
19258 __tmp.put_u8(self.manual_override_switch);
19259 if matches!(version, MavlinkVersion::V2) {
19260 let len = __tmp.len();
19261 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19262 } else {
19263 __tmp.len()
19264 }
19265 }
19266}
19267#[doc = "id: 41"]
19268#[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. Note that mission jump repeat counters are not reset (see MAV_CMD_DO_JUMP param2). This message may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this message must not trigger a switch to mission mode."]
19269#[derive(Debug, Clone, PartialEq)]
19270#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19271#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19272pub struct MISSION_SET_CURRENT_DATA {
19273 #[doc = "Sequence"]
19274 pub seq: u16,
19275 #[doc = "System ID"]
19276 pub target_system: u8,
19277 #[doc = "Component ID"]
19278 pub target_component: u8,
19279}
19280impl MISSION_SET_CURRENT_DATA {
19281 pub const ENCODED_LEN: usize = 4usize;
19282 pub const DEFAULT: Self = Self {
19283 seq: 0_u16,
19284 target_system: 0_u8,
19285 target_component: 0_u8,
19286 };
19287 #[cfg(feature = "arbitrary")]
19288 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19289 use arbitrary::{Arbitrary, Unstructured};
19290 let mut buf = [0u8; 1024];
19291 rng.fill_bytes(&mut buf);
19292 let mut unstructured = Unstructured::new(&buf);
19293 Self::arbitrary(&mut unstructured).unwrap_or_default()
19294 }
19295}
19296impl Default for MISSION_SET_CURRENT_DATA {
19297 fn default() -> Self {
19298 Self::DEFAULT.clone()
19299 }
19300}
19301impl MessageData for MISSION_SET_CURRENT_DATA {
19302 type Message = MavMessage;
19303 const ID: u32 = 41u32;
19304 const NAME: &'static str = "MISSION_SET_CURRENT";
19305 const EXTRA_CRC: u8 = 28u8;
19306 const ENCODED_LEN: usize = 4usize;
19307 fn deser(
19308 _version: MavlinkVersion,
19309 __input: &[u8],
19310 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19311 let avail_len = __input.len();
19312 let mut payload_buf = [0; Self::ENCODED_LEN];
19313 let mut buf = if avail_len < Self::ENCODED_LEN {
19314 payload_buf[0..avail_len].copy_from_slice(__input);
19315 Bytes::new(&payload_buf)
19316 } else {
19317 Bytes::new(__input)
19318 };
19319 let mut __struct = Self::default();
19320 __struct.seq = buf.get_u16_le();
19321 __struct.target_system = buf.get_u8();
19322 __struct.target_component = buf.get_u8();
19323 Ok(__struct)
19324 }
19325 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19326 let mut __tmp = BytesMut::new(bytes);
19327 #[allow(clippy::absurd_extreme_comparisons)]
19328 #[allow(unused_comparisons)]
19329 if __tmp.remaining() < Self::ENCODED_LEN {
19330 panic!(
19331 "buffer is too small (need {} bytes, but got {})",
19332 Self::ENCODED_LEN,
19333 __tmp.remaining(),
19334 )
19335 }
19336 __tmp.put_u16_le(self.seq);
19337 __tmp.put_u8(self.target_system);
19338 __tmp.put_u8(self.target_component);
19339 if matches!(version, MavlinkVersion::V2) {
19340 let len = __tmp.len();
19341 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19342 } else {
19343 __tmp.len()
19344 }
19345 }
19346}
19347#[doc = "id: 113"]
19348#[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate."]
19349#[derive(Debug, Clone, PartialEq)]
19350#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19351#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19352pub struct HIL_GPS_DATA {
19353 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
19354 pub time_usec: u64,
19355 #[doc = "Latitude (WGS84)"]
19356 pub lat: i32,
19357 #[doc = "Longitude (WGS84)"]
19358 pub lon: i32,
19359 #[doc = "Altitude (MSL). Positive for up."]
19360 pub alt: i32,
19361 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
19362 pub eph: u16,
19363 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
19364 pub epv: u16,
19365 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
19366 pub vel: u16,
19367 #[doc = "GPS velocity in north direction in earth-fixed NED frame"]
19368 pub vn: i16,
19369 #[doc = "GPS velocity in east direction in earth-fixed NED frame"]
19370 pub ve: i16,
19371 #[doc = "GPS velocity in down direction in earth-fixed NED frame"]
19372 pub vd: i16,
19373 #[doc = "Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
19374 pub cog: u16,
19375 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix."]
19376 pub fix_type: u8,
19377 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
19378 pub satellites_visible: u8,
19379 #[doc = "GPS ID (zero indexed). Used for multiple GPS inputs"]
19380 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19381 pub id: u8,
19382 #[doc = "Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north"]
19383 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19384 pub yaw: u16,
19385}
19386impl HIL_GPS_DATA {
19387 pub const ENCODED_LEN: usize = 39usize;
19388 pub const DEFAULT: Self = Self {
19389 time_usec: 0_u64,
19390 lat: 0_i32,
19391 lon: 0_i32,
19392 alt: 0_i32,
19393 eph: 0_u16,
19394 epv: 0_u16,
19395 vel: 0_u16,
19396 vn: 0_i16,
19397 ve: 0_i16,
19398 vd: 0_i16,
19399 cog: 0_u16,
19400 fix_type: 0_u8,
19401 satellites_visible: 0_u8,
19402 id: 0_u8,
19403 yaw: 0_u16,
19404 };
19405 #[cfg(feature = "arbitrary")]
19406 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19407 use arbitrary::{Arbitrary, Unstructured};
19408 let mut buf = [0u8; 1024];
19409 rng.fill_bytes(&mut buf);
19410 let mut unstructured = Unstructured::new(&buf);
19411 Self::arbitrary(&mut unstructured).unwrap_or_default()
19412 }
19413}
19414impl Default for HIL_GPS_DATA {
19415 fn default() -> Self {
19416 Self::DEFAULT.clone()
19417 }
19418}
19419impl MessageData for HIL_GPS_DATA {
19420 type Message = MavMessage;
19421 const ID: u32 = 113u32;
19422 const NAME: &'static str = "HIL_GPS";
19423 const EXTRA_CRC: u8 = 124u8;
19424 const ENCODED_LEN: usize = 39usize;
19425 fn deser(
19426 _version: MavlinkVersion,
19427 __input: &[u8],
19428 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19429 let avail_len = __input.len();
19430 let mut payload_buf = [0; Self::ENCODED_LEN];
19431 let mut buf = if avail_len < Self::ENCODED_LEN {
19432 payload_buf[0..avail_len].copy_from_slice(__input);
19433 Bytes::new(&payload_buf)
19434 } else {
19435 Bytes::new(__input)
19436 };
19437 let mut __struct = Self::default();
19438 __struct.time_usec = buf.get_u64_le();
19439 __struct.lat = buf.get_i32_le();
19440 __struct.lon = buf.get_i32_le();
19441 __struct.alt = buf.get_i32_le();
19442 __struct.eph = buf.get_u16_le();
19443 __struct.epv = buf.get_u16_le();
19444 __struct.vel = buf.get_u16_le();
19445 __struct.vn = buf.get_i16_le();
19446 __struct.ve = buf.get_i16_le();
19447 __struct.vd = buf.get_i16_le();
19448 __struct.cog = buf.get_u16_le();
19449 __struct.fix_type = buf.get_u8();
19450 __struct.satellites_visible = buf.get_u8();
19451 __struct.id = buf.get_u8();
19452 __struct.yaw = buf.get_u16_le();
19453 Ok(__struct)
19454 }
19455 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19456 let mut __tmp = BytesMut::new(bytes);
19457 #[allow(clippy::absurd_extreme_comparisons)]
19458 #[allow(unused_comparisons)]
19459 if __tmp.remaining() < Self::ENCODED_LEN {
19460 panic!(
19461 "buffer is too small (need {} bytes, but got {})",
19462 Self::ENCODED_LEN,
19463 __tmp.remaining(),
19464 )
19465 }
19466 __tmp.put_u64_le(self.time_usec);
19467 __tmp.put_i32_le(self.lat);
19468 __tmp.put_i32_le(self.lon);
19469 __tmp.put_i32_le(self.alt);
19470 __tmp.put_u16_le(self.eph);
19471 __tmp.put_u16_le(self.epv);
19472 __tmp.put_u16_le(self.vel);
19473 __tmp.put_i16_le(self.vn);
19474 __tmp.put_i16_le(self.ve);
19475 __tmp.put_i16_le(self.vd);
19476 __tmp.put_u16_le(self.cog);
19477 __tmp.put_u8(self.fix_type);
19478 __tmp.put_u8(self.satellites_visible);
19479 __tmp.put_u8(self.id);
19480 __tmp.put_u16_le(self.yaw);
19481 if matches!(version, MavlinkVersion::V2) {
19482 let len = __tmp.len();
19483 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19484 } else {
19485 __tmp.len()
19486 }
19487 }
19488}
19489#[doc = "id: 66"]
19490#[doc = "Request a data stream."]
19491#[derive(Debug, Clone, PartialEq)]
19492#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19493#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19494pub struct REQUEST_DATA_STREAM_DATA {
19495 #[doc = "The requested message rate"]
19496 pub req_message_rate: u16,
19497 #[doc = "The target requested to send the message stream."]
19498 pub target_system: u8,
19499 #[doc = "The target requested to send the message stream."]
19500 pub target_component: u8,
19501 #[doc = "The ID of the requested data stream"]
19502 pub req_stream_id: u8,
19503 #[doc = "1 to start sending, 0 to stop sending."]
19504 pub start_stop: u8,
19505}
19506impl REQUEST_DATA_STREAM_DATA {
19507 pub const ENCODED_LEN: usize = 6usize;
19508 pub const DEFAULT: Self = Self {
19509 req_message_rate: 0_u16,
19510 target_system: 0_u8,
19511 target_component: 0_u8,
19512 req_stream_id: 0_u8,
19513 start_stop: 0_u8,
19514 };
19515 #[cfg(feature = "arbitrary")]
19516 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19517 use arbitrary::{Arbitrary, Unstructured};
19518 let mut buf = [0u8; 1024];
19519 rng.fill_bytes(&mut buf);
19520 let mut unstructured = Unstructured::new(&buf);
19521 Self::arbitrary(&mut unstructured).unwrap_or_default()
19522 }
19523}
19524impl Default for REQUEST_DATA_STREAM_DATA {
19525 fn default() -> Self {
19526 Self::DEFAULT.clone()
19527 }
19528}
19529impl MessageData for REQUEST_DATA_STREAM_DATA {
19530 type Message = MavMessage;
19531 const ID: u32 = 66u32;
19532 const NAME: &'static str = "REQUEST_DATA_STREAM";
19533 const EXTRA_CRC: u8 = 148u8;
19534 const ENCODED_LEN: usize = 6usize;
19535 fn deser(
19536 _version: MavlinkVersion,
19537 __input: &[u8],
19538 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19539 let avail_len = __input.len();
19540 let mut payload_buf = [0; Self::ENCODED_LEN];
19541 let mut buf = if avail_len < Self::ENCODED_LEN {
19542 payload_buf[0..avail_len].copy_from_slice(__input);
19543 Bytes::new(&payload_buf)
19544 } else {
19545 Bytes::new(__input)
19546 };
19547 let mut __struct = Self::default();
19548 __struct.req_message_rate = buf.get_u16_le();
19549 __struct.target_system = buf.get_u8();
19550 __struct.target_component = buf.get_u8();
19551 __struct.req_stream_id = buf.get_u8();
19552 __struct.start_stop = buf.get_u8();
19553 Ok(__struct)
19554 }
19555 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19556 let mut __tmp = BytesMut::new(bytes);
19557 #[allow(clippy::absurd_extreme_comparisons)]
19558 #[allow(unused_comparisons)]
19559 if __tmp.remaining() < Self::ENCODED_LEN {
19560 panic!(
19561 "buffer is too small (need {} bytes, but got {})",
19562 Self::ENCODED_LEN,
19563 __tmp.remaining(),
19564 )
19565 }
19566 __tmp.put_u16_le(self.req_message_rate);
19567 __tmp.put_u8(self.target_system);
19568 __tmp.put_u8(self.target_component);
19569 __tmp.put_u8(self.req_stream_id);
19570 __tmp.put_u8(self.start_stop);
19571 if matches!(version, MavlinkVersion::V2) {
19572 let len = __tmp.len();
19573 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19574 } else {
19575 __tmp.len()
19576 }
19577 }
19578}
19579#[doc = "id: 234"]
19580#[doc = "Message appropriate for high latency connections like Iridium."]
19581#[derive(Debug, Clone, PartialEq)]
19582#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19583#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19584pub struct HIGH_LATENCY_DATA {
19585 #[doc = "A bitfield for use for autopilot-specific flags."]
19586 pub custom_mode: u32,
19587 #[doc = "Latitude"]
19588 pub latitude: i32,
19589 #[doc = "Longitude"]
19590 pub longitude: i32,
19591 #[doc = "roll"]
19592 pub roll: i16,
19593 #[doc = "pitch"]
19594 pub pitch: i16,
19595 #[doc = "heading"]
19596 pub heading: u16,
19597 #[doc = "heading setpoint"]
19598 pub heading_sp: i16,
19599 #[doc = "Altitude above mean sea level"]
19600 pub altitude_amsl: i16,
19601 #[doc = "Altitude setpoint relative to the home position"]
19602 pub altitude_sp: i16,
19603 #[doc = "distance to target"]
19604 pub wp_distance: u16,
19605 #[doc = "Bitmap of enabled system modes."]
19606 pub base_mode: MavModeFlag,
19607 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
19608 pub landed_state: MavLandedState,
19609 #[doc = "throttle (percentage)"]
19610 pub throttle: i8,
19611 #[doc = "airspeed"]
19612 pub airspeed: u8,
19613 #[doc = "airspeed setpoint"]
19614 pub airspeed_sp: u8,
19615 #[doc = "groundspeed"]
19616 pub groundspeed: u8,
19617 #[doc = "climb rate"]
19618 pub climb_rate: i8,
19619 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
19620 pub gps_nsat: u8,
19621 #[doc = "GPS Fix type."]
19622 pub gps_fix_type: GpsFixType,
19623 #[doc = "Remaining battery (percentage)"]
19624 pub battery_remaining: u8,
19625 #[doc = "Autopilot temperature (degrees C)"]
19626 pub temperature: i8,
19627 #[doc = "Air temperature (degrees C) from airspeed sensor"]
19628 pub temperature_air: i8,
19629 #[doc = "failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)"]
19630 pub failsafe: u8,
19631 #[doc = "current waypoint number"]
19632 pub wp_num: u8,
19633}
19634impl HIGH_LATENCY_DATA {
19635 pub const ENCODED_LEN: usize = 40usize;
19636 pub const DEFAULT: Self = Self {
19637 custom_mode: 0_u32,
19638 latitude: 0_i32,
19639 longitude: 0_i32,
19640 roll: 0_i16,
19641 pitch: 0_i16,
19642 heading: 0_u16,
19643 heading_sp: 0_i16,
19644 altitude_amsl: 0_i16,
19645 altitude_sp: 0_i16,
19646 wp_distance: 0_u16,
19647 base_mode: MavModeFlag::DEFAULT,
19648 landed_state: MavLandedState::DEFAULT,
19649 throttle: 0_i8,
19650 airspeed: 0_u8,
19651 airspeed_sp: 0_u8,
19652 groundspeed: 0_u8,
19653 climb_rate: 0_i8,
19654 gps_nsat: 0_u8,
19655 gps_fix_type: GpsFixType::DEFAULT,
19656 battery_remaining: 0_u8,
19657 temperature: 0_i8,
19658 temperature_air: 0_i8,
19659 failsafe: 0_u8,
19660 wp_num: 0_u8,
19661 };
19662 #[cfg(feature = "arbitrary")]
19663 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19664 use arbitrary::{Arbitrary, Unstructured};
19665 let mut buf = [0u8; 1024];
19666 rng.fill_bytes(&mut buf);
19667 let mut unstructured = Unstructured::new(&buf);
19668 Self::arbitrary(&mut unstructured).unwrap_or_default()
19669 }
19670}
19671impl Default for HIGH_LATENCY_DATA {
19672 fn default() -> Self {
19673 Self::DEFAULT.clone()
19674 }
19675}
19676impl MessageData for HIGH_LATENCY_DATA {
19677 type Message = MavMessage;
19678 const ID: u32 = 234u32;
19679 const NAME: &'static str = "HIGH_LATENCY";
19680 const EXTRA_CRC: u8 = 150u8;
19681 const ENCODED_LEN: usize = 40usize;
19682 fn deser(
19683 _version: MavlinkVersion,
19684 __input: &[u8],
19685 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19686 let avail_len = __input.len();
19687 let mut payload_buf = [0; Self::ENCODED_LEN];
19688 let mut buf = if avail_len < Self::ENCODED_LEN {
19689 payload_buf[0..avail_len].copy_from_slice(__input);
19690 Bytes::new(&payload_buf)
19691 } else {
19692 Bytes::new(__input)
19693 };
19694 let mut __struct = Self::default();
19695 __struct.custom_mode = buf.get_u32_le();
19696 __struct.latitude = buf.get_i32_le();
19697 __struct.longitude = buf.get_i32_le();
19698 __struct.roll = buf.get_i16_le();
19699 __struct.pitch = buf.get_i16_le();
19700 __struct.heading = buf.get_u16_le();
19701 __struct.heading_sp = buf.get_i16_le();
19702 __struct.altitude_amsl = buf.get_i16_le();
19703 __struct.altitude_sp = buf.get_i16_le();
19704 __struct.wp_distance = buf.get_u16_le();
19705 let tmp = buf.get_u8();
19706 __struct.base_mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
19707 ::mavlink_core::error::ParserError::InvalidFlag {
19708 flag_type: "MavModeFlag",
19709 value: tmp as u32,
19710 },
19711 )?;
19712 let tmp = buf.get_u8();
19713 __struct.landed_state =
19714 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19715 enum_type: "MavLandedState",
19716 value: tmp as u32,
19717 })?;
19718 __struct.throttle = buf.get_i8();
19719 __struct.airspeed = buf.get_u8();
19720 __struct.airspeed_sp = buf.get_u8();
19721 __struct.groundspeed = buf.get_u8();
19722 __struct.climb_rate = buf.get_i8();
19723 __struct.gps_nsat = buf.get_u8();
19724 let tmp = buf.get_u8();
19725 __struct.gps_fix_type =
19726 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19727 enum_type: "GpsFixType",
19728 value: tmp as u32,
19729 })?;
19730 __struct.battery_remaining = buf.get_u8();
19731 __struct.temperature = buf.get_i8();
19732 __struct.temperature_air = buf.get_i8();
19733 __struct.failsafe = buf.get_u8();
19734 __struct.wp_num = buf.get_u8();
19735 Ok(__struct)
19736 }
19737 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19738 let mut __tmp = BytesMut::new(bytes);
19739 #[allow(clippy::absurd_extreme_comparisons)]
19740 #[allow(unused_comparisons)]
19741 if __tmp.remaining() < Self::ENCODED_LEN {
19742 panic!(
19743 "buffer is too small (need {} bytes, but got {})",
19744 Self::ENCODED_LEN,
19745 __tmp.remaining(),
19746 )
19747 }
19748 __tmp.put_u32_le(self.custom_mode);
19749 __tmp.put_i32_le(self.latitude);
19750 __tmp.put_i32_le(self.longitude);
19751 __tmp.put_i16_le(self.roll);
19752 __tmp.put_i16_le(self.pitch);
19753 __tmp.put_u16_le(self.heading);
19754 __tmp.put_i16_le(self.heading_sp);
19755 __tmp.put_i16_le(self.altitude_amsl);
19756 __tmp.put_i16_le(self.altitude_sp);
19757 __tmp.put_u16_le(self.wp_distance);
19758 __tmp.put_u8(self.base_mode.bits());
19759 __tmp.put_u8(self.landed_state as u8);
19760 __tmp.put_i8(self.throttle);
19761 __tmp.put_u8(self.airspeed);
19762 __tmp.put_u8(self.airspeed_sp);
19763 __tmp.put_u8(self.groundspeed);
19764 __tmp.put_i8(self.climb_rate);
19765 __tmp.put_u8(self.gps_nsat);
19766 __tmp.put_u8(self.gps_fix_type as u8);
19767 __tmp.put_u8(self.battery_remaining);
19768 __tmp.put_i8(self.temperature);
19769 __tmp.put_i8(self.temperature_air);
19770 __tmp.put_u8(self.failsafe);
19771 __tmp.put_u8(self.wp_num);
19772 if matches!(version, MavlinkVersion::V2) {
19773 let len = __tmp.len();
19774 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19775 } else {
19776 __tmp.len()
19777 }
19778 }
19779}
19780#[doc = "id: 264"]
19781#[doc = "Flight information. This includes time since boot for arm, takeoff, and land, and a flight number. Takeoff and landing values reset to zero on arm. This can be requested using MAV_CMD_REQUEST_MESSAGE. Note, some fields are misnamed - timestamps are from boot (not UTC) and the flight_uuid is a sequence number."]
19782#[derive(Debug, Clone, PartialEq)]
19783#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19784#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19785pub struct FLIGHT_INFORMATION_DATA {
19786 #[doc = "Timestamp at arming (since system boot). Set to 0 on boot. Set value on arming. Note, field is misnamed UTC."]
19787 pub arming_time_utc: u64,
19788 #[doc = "Timestamp at takeoff (since system boot). Set to 0 at boot and on arming. Note, field is misnamed UTC."]
19789 pub takeoff_time_utc: u64,
19790 #[doc = "Flight number. Note, field is misnamed UUID."]
19791 pub flight_uuid: u64,
19792 #[doc = "Timestamp (time since system boot)."]
19793 pub time_boot_ms: u32,
19794 #[doc = "Timestamp at landing (in ms since system boot). Set to 0 at boot and on arming."]
19795 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19796 pub landing_time: u32,
19797}
19798impl FLIGHT_INFORMATION_DATA {
19799 pub const ENCODED_LEN: usize = 32usize;
19800 pub const DEFAULT: Self = Self {
19801 arming_time_utc: 0_u64,
19802 takeoff_time_utc: 0_u64,
19803 flight_uuid: 0_u64,
19804 time_boot_ms: 0_u32,
19805 landing_time: 0_u32,
19806 };
19807 #[cfg(feature = "arbitrary")]
19808 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19809 use arbitrary::{Arbitrary, Unstructured};
19810 let mut buf = [0u8; 1024];
19811 rng.fill_bytes(&mut buf);
19812 let mut unstructured = Unstructured::new(&buf);
19813 Self::arbitrary(&mut unstructured).unwrap_or_default()
19814 }
19815}
19816impl Default for FLIGHT_INFORMATION_DATA {
19817 fn default() -> Self {
19818 Self::DEFAULT.clone()
19819 }
19820}
19821impl MessageData for FLIGHT_INFORMATION_DATA {
19822 type Message = MavMessage;
19823 const ID: u32 = 264u32;
19824 const NAME: &'static str = "FLIGHT_INFORMATION";
19825 const EXTRA_CRC: u8 = 49u8;
19826 const ENCODED_LEN: usize = 32usize;
19827 fn deser(
19828 _version: MavlinkVersion,
19829 __input: &[u8],
19830 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19831 let avail_len = __input.len();
19832 let mut payload_buf = [0; Self::ENCODED_LEN];
19833 let mut buf = if avail_len < Self::ENCODED_LEN {
19834 payload_buf[0..avail_len].copy_from_slice(__input);
19835 Bytes::new(&payload_buf)
19836 } else {
19837 Bytes::new(__input)
19838 };
19839 let mut __struct = Self::default();
19840 __struct.arming_time_utc = buf.get_u64_le();
19841 __struct.takeoff_time_utc = buf.get_u64_le();
19842 __struct.flight_uuid = buf.get_u64_le();
19843 __struct.time_boot_ms = buf.get_u32_le();
19844 __struct.landing_time = buf.get_u32_le();
19845 Ok(__struct)
19846 }
19847 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19848 let mut __tmp = BytesMut::new(bytes);
19849 #[allow(clippy::absurd_extreme_comparisons)]
19850 #[allow(unused_comparisons)]
19851 if __tmp.remaining() < Self::ENCODED_LEN {
19852 panic!(
19853 "buffer is too small (need {} bytes, but got {})",
19854 Self::ENCODED_LEN,
19855 __tmp.remaining(),
19856 )
19857 }
19858 __tmp.put_u64_le(self.arming_time_utc);
19859 __tmp.put_u64_le(self.takeoff_time_utc);
19860 __tmp.put_u64_le(self.flight_uuid);
19861 __tmp.put_u32_le(self.time_boot_ms);
19862 __tmp.put_u32_le(self.landing_time);
19863 if matches!(version, MavlinkVersion::V2) {
19864 let len = __tmp.len();
19865 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19866 } else {
19867 __tmp.len()
19868 }
19869 }
19870}
19871#[doc = "id: 126"]
19872#[doc = "Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate."]
19873#[derive(Debug, Clone, PartialEq)]
19874#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19875#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19876pub struct SERIAL_CONTROL_DATA {
19877 #[doc = "Baudrate of transfer. Zero means no change."]
19878 pub baudrate: u32,
19879 #[doc = "Timeout for reply data"]
19880 pub timeout: u16,
19881 #[doc = "Serial control device type."]
19882 pub device: SerialControlDev,
19883 #[doc = "Bitmap of serial control flags."]
19884 pub flags: SerialControlFlag,
19885 #[doc = "how many bytes in this transfer"]
19886 pub count: u8,
19887 #[doc = "serial data"]
19888 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19889 pub data: [u8; 70],
19890 #[doc = "System ID"]
19891 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19892 pub target_system: u8,
19893 #[doc = "Component ID"]
19894 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19895 pub target_component: u8,
19896}
19897impl SERIAL_CONTROL_DATA {
19898 pub const ENCODED_LEN: usize = 81usize;
19899 pub const DEFAULT: Self = Self {
19900 baudrate: 0_u32,
19901 timeout: 0_u16,
19902 device: SerialControlDev::DEFAULT,
19903 flags: SerialControlFlag::DEFAULT,
19904 count: 0_u8,
19905 data: [0_u8; 70usize],
19906 target_system: 0_u8,
19907 target_component: 0_u8,
19908 };
19909 #[cfg(feature = "arbitrary")]
19910 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19911 use arbitrary::{Arbitrary, Unstructured};
19912 let mut buf = [0u8; 1024];
19913 rng.fill_bytes(&mut buf);
19914 let mut unstructured = Unstructured::new(&buf);
19915 Self::arbitrary(&mut unstructured).unwrap_or_default()
19916 }
19917}
19918impl Default for SERIAL_CONTROL_DATA {
19919 fn default() -> Self {
19920 Self::DEFAULT.clone()
19921 }
19922}
19923impl MessageData for SERIAL_CONTROL_DATA {
19924 type Message = MavMessage;
19925 const ID: u32 = 126u32;
19926 const NAME: &'static str = "SERIAL_CONTROL";
19927 const EXTRA_CRC: u8 = 220u8;
19928 const ENCODED_LEN: usize = 81usize;
19929 fn deser(
19930 _version: MavlinkVersion,
19931 __input: &[u8],
19932 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19933 let avail_len = __input.len();
19934 let mut payload_buf = [0; Self::ENCODED_LEN];
19935 let mut buf = if avail_len < Self::ENCODED_LEN {
19936 payload_buf[0..avail_len].copy_from_slice(__input);
19937 Bytes::new(&payload_buf)
19938 } else {
19939 Bytes::new(__input)
19940 };
19941 let mut __struct = Self::default();
19942 __struct.baudrate = buf.get_u32_le();
19943 __struct.timeout = buf.get_u16_le();
19944 let tmp = buf.get_u8();
19945 __struct.device =
19946 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19947 enum_type: "SerialControlDev",
19948 value: tmp as u32,
19949 })?;
19950 let tmp = buf.get_u8();
19951 __struct.flags = SerialControlFlag::from_bits(tmp & SerialControlFlag::all().bits())
19952 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
19953 flag_type: "SerialControlFlag",
19954 value: tmp as u32,
19955 })?;
19956 __struct.count = buf.get_u8();
19957 for v in &mut __struct.data {
19958 let val = buf.get_u8();
19959 *v = val;
19960 }
19961 __struct.target_system = buf.get_u8();
19962 __struct.target_component = buf.get_u8();
19963 Ok(__struct)
19964 }
19965 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19966 let mut __tmp = BytesMut::new(bytes);
19967 #[allow(clippy::absurd_extreme_comparisons)]
19968 #[allow(unused_comparisons)]
19969 if __tmp.remaining() < Self::ENCODED_LEN {
19970 panic!(
19971 "buffer is too small (need {} bytes, but got {})",
19972 Self::ENCODED_LEN,
19973 __tmp.remaining(),
19974 )
19975 }
19976 __tmp.put_u32_le(self.baudrate);
19977 __tmp.put_u16_le(self.timeout);
19978 __tmp.put_u8(self.device as u8);
19979 __tmp.put_u8(self.flags.bits());
19980 __tmp.put_u8(self.count);
19981 for val in &self.data {
19982 __tmp.put_u8(*val);
19983 }
19984 __tmp.put_u8(self.target_system);
19985 __tmp.put_u8(self.target_component);
19986 if matches!(version, MavlinkVersion::V2) {
19987 let len = __tmp.len();
19988 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19989 } else {
19990 __tmp.len()
19991 }
19992 }
19993}
19994#[doc = "id: 75"]
19995#[doc = "Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG as it allows the MAV_FRAME to be specified for interpreting positional information, such as altitude. COMMAND_INT is also preferred when sending latitude and longitude data in params 5 and 6, as it allows for greater precision. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
19996#[derive(Debug, Clone, PartialEq)]
19997#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19998#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19999pub struct COMMAND_INT_DATA {
20000 #[doc = "PARAM1, see MAV_CMD enum"]
20001 pub param1: f32,
20002 #[doc = "PARAM2, see MAV_CMD enum"]
20003 pub param2: f32,
20004 #[doc = "PARAM3, see MAV_CMD enum"]
20005 pub param3: f32,
20006 #[doc = "PARAM4, see MAV_CMD enum"]
20007 pub param4: f32,
20008 #[doc = "PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7"]
20009 pub x: i32,
20010 #[doc = "PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7"]
20011 pub y: i32,
20012 #[doc = "PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame)."]
20013 pub z: f32,
20014 #[doc = "The scheduled action for the mission item."]
20015 pub command: MavCmd,
20016 #[doc = "System ID"]
20017 pub target_system: u8,
20018 #[doc = "Component ID"]
20019 pub target_component: u8,
20020 #[doc = "The coordinate system of the COMMAND."]
20021 pub frame: MavFrame,
20022 #[doc = "Not used."]
20023 pub current: u8,
20024 #[doc = "Not used (set 0)."]
20025 pub autocontinue: u8,
20026}
20027impl COMMAND_INT_DATA {
20028 pub const ENCODED_LEN: usize = 35usize;
20029 pub const DEFAULT: Self = Self {
20030 param1: 0.0_f32,
20031 param2: 0.0_f32,
20032 param3: 0.0_f32,
20033 param4: 0.0_f32,
20034 x: 0_i32,
20035 y: 0_i32,
20036 z: 0.0_f32,
20037 command: MavCmd::DEFAULT,
20038 target_system: 0_u8,
20039 target_component: 0_u8,
20040 frame: MavFrame::DEFAULT,
20041 current: 0_u8,
20042 autocontinue: 0_u8,
20043 };
20044 #[cfg(feature = "arbitrary")]
20045 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20046 use arbitrary::{Arbitrary, Unstructured};
20047 let mut buf = [0u8; 1024];
20048 rng.fill_bytes(&mut buf);
20049 let mut unstructured = Unstructured::new(&buf);
20050 Self::arbitrary(&mut unstructured).unwrap_or_default()
20051 }
20052}
20053impl Default for COMMAND_INT_DATA {
20054 fn default() -> Self {
20055 Self::DEFAULT.clone()
20056 }
20057}
20058impl MessageData for COMMAND_INT_DATA {
20059 type Message = MavMessage;
20060 const ID: u32 = 75u32;
20061 const NAME: &'static str = "COMMAND_INT";
20062 const EXTRA_CRC: u8 = 158u8;
20063 const ENCODED_LEN: usize = 35usize;
20064 fn deser(
20065 _version: MavlinkVersion,
20066 __input: &[u8],
20067 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20068 let avail_len = __input.len();
20069 let mut payload_buf = [0; Self::ENCODED_LEN];
20070 let mut buf = if avail_len < Self::ENCODED_LEN {
20071 payload_buf[0..avail_len].copy_from_slice(__input);
20072 Bytes::new(&payload_buf)
20073 } else {
20074 Bytes::new(__input)
20075 };
20076 let mut __struct = Self::default();
20077 __struct.param1 = buf.get_f32_le();
20078 __struct.param2 = buf.get_f32_le();
20079 __struct.param3 = buf.get_f32_le();
20080 __struct.param4 = buf.get_f32_le();
20081 __struct.x = buf.get_i32_le();
20082 __struct.y = buf.get_i32_le();
20083 __struct.z = buf.get_f32_le();
20084 let tmp = buf.get_u16_le();
20085 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
20086 ::mavlink_core::error::ParserError::InvalidEnum {
20087 enum_type: "MavCmd",
20088 value: tmp as u32,
20089 },
20090 )?;
20091 __struct.target_system = buf.get_u8();
20092 __struct.target_component = buf.get_u8();
20093 let tmp = buf.get_u8();
20094 __struct.frame =
20095 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20096 enum_type: "MavFrame",
20097 value: tmp as u32,
20098 })?;
20099 __struct.current = buf.get_u8();
20100 __struct.autocontinue = buf.get_u8();
20101 Ok(__struct)
20102 }
20103 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20104 let mut __tmp = BytesMut::new(bytes);
20105 #[allow(clippy::absurd_extreme_comparisons)]
20106 #[allow(unused_comparisons)]
20107 if __tmp.remaining() < Self::ENCODED_LEN {
20108 panic!(
20109 "buffer is too small (need {} bytes, but got {})",
20110 Self::ENCODED_LEN,
20111 __tmp.remaining(),
20112 )
20113 }
20114 __tmp.put_f32_le(self.param1);
20115 __tmp.put_f32_le(self.param2);
20116 __tmp.put_f32_le(self.param3);
20117 __tmp.put_f32_le(self.param4);
20118 __tmp.put_i32_le(self.x);
20119 __tmp.put_i32_le(self.y);
20120 __tmp.put_f32_le(self.z);
20121 __tmp.put_u16_le(self.command as u16);
20122 __tmp.put_u8(self.target_system);
20123 __tmp.put_u8(self.target_component);
20124 __tmp.put_u8(self.frame as u8);
20125 __tmp.put_u8(self.current);
20126 __tmp.put_u8(self.autocontinue);
20127 if matches!(version, MavlinkVersion::V2) {
20128 let len = __tmp.len();
20129 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20130 } else {
20131 __tmp.len()
20132 }
20133 }
20134}
20135#[doc = "id: 259"]
20136#[doc = "Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
20137#[derive(Debug, Clone, PartialEq)]
20138#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20139#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20140pub struct CAMERA_INFORMATION_DATA {
20141 #[doc = "Timestamp (time since system boot)."]
20142 pub time_boot_ms: u32,
20143 #[doc = "0xff). Use 0 if not known."]
20144 pub firmware_version: u32,
20145 #[doc = "Focal length. Use NaN if not known."]
20146 pub focal_length: f32,
20147 #[doc = "Image sensor size horizontal. Use NaN if not known."]
20148 pub sensor_size_h: f32,
20149 #[doc = "Image sensor size vertical. Use NaN if not known."]
20150 pub sensor_size_v: f32,
20151 #[doc = "Bitmap of camera capability flags."]
20152 pub flags: CameraCapFlags,
20153 #[doc = "Horizontal image resolution. Use 0 if not known."]
20154 pub resolution_h: u16,
20155 #[doc = "Vertical image resolution. Use 0 if not known."]
20156 pub resolution_v: u16,
20157 #[doc = "Camera definition version (iteration). Use 0 if not known."]
20158 pub cam_definition_version: u16,
20159 #[doc = "Name of the camera vendor"]
20160 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20161 pub vendor_name: [u8; 32],
20162 #[doc = "Name of the camera model"]
20163 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20164 pub model_name: [u8; 32],
20165 #[doc = "Reserved for a lens ID. Use 0 if not known."]
20166 pub lens_id: u8,
20167 #[doc = "Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known."]
20168 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20169 pub cam_definition_uri: [u8; 140],
20170 #[doc = "Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera."]
20171 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20172 pub gimbal_device_id: u8,
20173 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
20174 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20175 pub camera_device_id: u8,
20176}
20177impl CAMERA_INFORMATION_DATA {
20178 pub const ENCODED_LEN: usize = 237usize;
20179 pub const DEFAULT: Self = Self {
20180 time_boot_ms: 0_u32,
20181 firmware_version: 0_u32,
20182 focal_length: 0.0_f32,
20183 sensor_size_h: 0.0_f32,
20184 sensor_size_v: 0.0_f32,
20185 flags: CameraCapFlags::DEFAULT,
20186 resolution_h: 0_u16,
20187 resolution_v: 0_u16,
20188 cam_definition_version: 0_u16,
20189 vendor_name: [0_u8; 32usize],
20190 model_name: [0_u8; 32usize],
20191 lens_id: 0_u8,
20192 cam_definition_uri: [0_u8; 140usize],
20193 gimbal_device_id: 0_u8,
20194 camera_device_id: 0_u8,
20195 };
20196 #[cfg(feature = "arbitrary")]
20197 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20198 use arbitrary::{Arbitrary, Unstructured};
20199 let mut buf = [0u8; 1024];
20200 rng.fill_bytes(&mut buf);
20201 let mut unstructured = Unstructured::new(&buf);
20202 Self::arbitrary(&mut unstructured).unwrap_or_default()
20203 }
20204}
20205impl Default for CAMERA_INFORMATION_DATA {
20206 fn default() -> Self {
20207 Self::DEFAULT.clone()
20208 }
20209}
20210impl MessageData for CAMERA_INFORMATION_DATA {
20211 type Message = MavMessage;
20212 const ID: u32 = 259u32;
20213 const NAME: &'static str = "CAMERA_INFORMATION";
20214 const EXTRA_CRC: u8 = 92u8;
20215 const ENCODED_LEN: usize = 237usize;
20216 fn deser(
20217 _version: MavlinkVersion,
20218 __input: &[u8],
20219 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20220 let avail_len = __input.len();
20221 let mut payload_buf = [0; Self::ENCODED_LEN];
20222 let mut buf = if avail_len < Self::ENCODED_LEN {
20223 payload_buf[0..avail_len].copy_from_slice(__input);
20224 Bytes::new(&payload_buf)
20225 } else {
20226 Bytes::new(__input)
20227 };
20228 let mut __struct = Self::default();
20229 __struct.time_boot_ms = buf.get_u32_le();
20230 __struct.firmware_version = buf.get_u32_le();
20231 __struct.focal_length = buf.get_f32_le();
20232 __struct.sensor_size_h = buf.get_f32_le();
20233 __struct.sensor_size_v = buf.get_f32_le();
20234 let tmp = buf.get_u32_le();
20235 __struct.flags = CameraCapFlags::from_bits(tmp & CameraCapFlags::all().bits()).ok_or(
20236 ::mavlink_core::error::ParserError::InvalidFlag {
20237 flag_type: "CameraCapFlags",
20238 value: tmp as u32,
20239 },
20240 )?;
20241 __struct.resolution_h = buf.get_u16_le();
20242 __struct.resolution_v = buf.get_u16_le();
20243 __struct.cam_definition_version = buf.get_u16_le();
20244 for v in &mut __struct.vendor_name {
20245 let val = buf.get_u8();
20246 *v = val;
20247 }
20248 for v in &mut __struct.model_name {
20249 let val = buf.get_u8();
20250 *v = val;
20251 }
20252 __struct.lens_id = buf.get_u8();
20253 for v in &mut __struct.cam_definition_uri {
20254 let val = buf.get_u8();
20255 *v = val;
20256 }
20257 __struct.gimbal_device_id = buf.get_u8();
20258 __struct.camera_device_id = buf.get_u8();
20259 Ok(__struct)
20260 }
20261 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20262 let mut __tmp = BytesMut::new(bytes);
20263 #[allow(clippy::absurd_extreme_comparisons)]
20264 #[allow(unused_comparisons)]
20265 if __tmp.remaining() < Self::ENCODED_LEN {
20266 panic!(
20267 "buffer is too small (need {} bytes, but got {})",
20268 Self::ENCODED_LEN,
20269 __tmp.remaining(),
20270 )
20271 }
20272 __tmp.put_u32_le(self.time_boot_ms);
20273 __tmp.put_u32_le(self.firmware_version);
20274 __tmp.put_f32_le(self.focal_length);
20275 __tmp.put_f32_le(self.sensor_size_h);
20276 __tmp.put_f32_le(self.sensor_size_v);
20277 __tmp.put_u32_le(self.flags.bits());
20278 __tmp.put_u16_le(self.resolution_h);
20279 __tmp.put_u16_le(self.resolution_v);
20280 __tmp.put_u16_le(self.cam_definition_version);
20281 for val in &self.vendor_name {
20282 __tmp.put_u8(*val);
20283 }
20284 for val in &self.model_name {
20285 __tmp.put_u8(*val);
20286 }
20287 __tmp.put_u8(self.lens_id);
20288 for val in &self.cam_definition_uri {
20289 __tmp.put_u8(*val);
20290 }
20291 __tmp.put_u8(self.gimbal_device_id);
20292 __tmp.put_u8(self.camera_device_id);
20293 if matches!(version, MavlinkVersion::V2) {
20294 let len = __tmp.len();
20295 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20296 } else {
20297 __tmp.len()
20298 }
20299 }
20300}
20301#[doc = "id: 108"]
20302#[doc = "Status of simulation environment, if used."]
20303#[derive(Debug, Clone, PartialEq)]
20304#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20305#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20306pub struct SIM_STATE_DATA {
20307 #[doc = "True attitude quaternion component 1, w (1 in null-rotation)"]
20308 pub q1: f32,
20309 #[doc = "True attitude quaternion component 2, x (0 in null-rotation)"]
20310 pub q2: f32,
20311 #[doc = "True attitude quaternion component 3, y (0 in null-rotation)"]
20312 pub q3: f32,
20313 #[doc = "True attitude quaternion component 4, z (0 in null-rotation)"]
20314 pub q4: f32,
20315 #[doc = "Attitude roll expressed as Euler angles, not recommended except for human-readable outputs"]
20316 pub roll: f32,
20317 #[doc = "Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs"]
20318 pub pitch: f32,
20319 #[doc = "Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs"]
20320 pub yaw: f32,
20321 #[doc = "X acceleration"]
20322 pub xacc: f32,
20323 #[doc = "Y acceleration"]
20324 pub yacc: f32,
20325 #[doc = "Z acceleration"]
20326 pub zacc: f32,
20327 #[doc = "Angular speed around X axis"]
20328 pub xgyro: f32,
20329 #[doc = "Angular speed around Y axis"]
20330 pub ygyro: f32,
20331 #[doc = "Angular speed around Z axis"]
20332 pub zgyro: f32,
20333 #[doc = "Latitude (lower precision). Both this and the lat_int field should be set."]
20334 pub lat: f32,
20335 #[doc = "Longitude (lower precision). Both this and the lon_int field should be set."]
20336 pub lon: f32,
20337 #[doc = "Altitude"]
20338 pub alt: f32,
20339 #[doc = "Horizontal position standard deviation"]
20340 pub std_dev_horz: f32,
20341 #[doc = "Vertical position standard deviation"]
20342 pub std_dev_vert: f32,
20343 #[doc = "True velocity in north direction in earth-fixed NED frame"]
20344 pub vn: f32,
20345 #[doc = "True velocity in east direction in earth-fixed NED frame"]
20346 pub ve: f32,
20347 #[doc = "True velocity in down direction in earth-fixed NED frame"]
20348 pub vd: f32,
20349 #[doc = "Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred)."]
20350 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20351 pub lat_int: i32,
20352 #[doc = "Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred)."]
20353 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20354 pub lon_int: i32,
20355}
20356impl SIM_STATE_DATA {
20357 pub const ENCODED_LEN: usize = 92usize;
20358 pub const DEFAULT: Self = Self {
20359 q1: 0.0_f32,
20360 q2: 0.0_f32,
20361 q3: 0.0_f32,
20362 q4: 0.0_f32,
20363 roll: 0.0_f32,
20364 pitch: 0.0_f32,
20365 yaw: 0.0_f32,
20366 xacc: 0.0_f32,
20367 yacc: 0.0_f32,
20368 zacc: 0.0_f32,
20369 xgyro: 0.0_f32,
20370 ygyro: 0.0_f32,
20371 zgyro: 0.0_f32,
20372 lat: 0.0_f32,
20373 lon: 0.0_f32,
20374 alt: 0.0_f32,
20375 std_dev_horz: 0.0_f32,
20376 std_dev_vert: 0.0_f32,
20377 vn: 0.0_f32,
20378 ve: 0.0_f32,
20379 vd: 0.0_f32,
20380 lat_int: 0_i32,
20381 lon_int: 0_i32,
20382 };
20383 #[cfg(feature = "arbitrary")]
20384 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20385 use arbitrary::{Arbitrary, Unstructured};
20386 let mut buf = [0u8; 1024];
20387 rng.fill_bytes(&mut buf);
20388 let mut unstructured = Unstructured::new(&buf);
20389 Self::arbitrary(&mut unstructured).unwrap_or_default()
20390 }
20391}
20392impl Default for SIM_STATE_DATA {
20393 fn default() -> Self {
20394 Self::DEFAULT.clone()
20395 }
20396}
20397impl MessageData for SIM_STATE_DATA {
20398 type Message = MavMessage;
20399 const ID: u32 = 108u32;
20400 const NAME: &'static str = "SIM_STATE";
20401 const EXTRA_CRC: u8 = 32u8;
20402 const ENCODED_LEN: usize = 92usize;
20403 fn deser(
20404 _version: MavlinkVersion,
20405 __input: &[u8],
20406 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20407 let avail_len = __input.len();
20408 let mut payload_buf = [0; Self::ENCODED_LEN];
20409 let mut buf = if avail_len < Self::ENCODED_LEN {
20410 payload_buf[0..avail_len].copy_from_slice(__input);
20411 Bytes::new(&payload_buf)
20412 } else {
20413 Bytes::new(__input)
20414 };
20415 let mut __struct = Self::default();
20416 __struct.q1 = buf.get_f32_le();
20417 __struct.q2 = buf.get_f32_le();
20418 __struct.q3 = buf.get_f32_le();
20419 __struct.q4 = buf.get_f32_le();
20420 __struct.roll = buf.get_f32_le();
20421 __struct.pitch = buf.get_f32_le();
20422 __struct.yaw = buf.get_f32_le();
20423 __struct.xacc = buf.get_f32_le();
20424 __struct.yacc = buf.get_f32_le();
20425 __struct.zacc = buf.get_f32_le();
20426 __struct.xgyro = buf.get_f32_le();
20427 __struct.ygyro = buf.get_f32_le();
20428 __struct.zgyro = buf.get_f32_le();
20429 __struct.lat = buf.get_f32_le();
20430 __struct.lon = buf.get_f32_le();
20431 __struct.alt = buf.get_f32_le();
20432 __struct.std_dev_horz = buf.get_f32_le();
20433 __struct.std_dev_vert = buf.get_f32_le();
20434 __struct.vn = buf.get_f32_le();
20435 __struct.ve = buf.get_f32_le();
20436 __struct.vd = buf.get_f32_le();
20437 __struct.lat_int = buf.get_i32_le();
20438 __struct.lon_int = buf.get_i32_le();
20439 Ok(__struct)
20440 }
20441 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20442 let mut __tmp = BytesMut::new(bytes);
20443 #[allow(clippy::absurd_extreme_comparisons)]
20444 #[allow(unused_comparisons)]
20445 if __tmp.remaining() < Self::ENCODED_LEN {
20446 panic!(
20447 "buffer is too small (need {} bytes, but got {})",
20448 Self::ENCODED_LEN,
20449 __tmp.remaining(),
20450 )
20451 }
20452 __tmp.put_f32_le(self.q1);
20453 __tmp.put_f32_le(self.q2);
20454 __tmp.put_f32_le(self.q3);
20455 __tmp.put_f32_le(self.q4);
20456 __tmp.put_f32_le(self.roll);
20457 __tmp.put_f32_le(self.pitch);
20458 __tmp.put_f32_le(self.yaw);
20459 __tmp.put_f32_le(self.xacc);
20460 __tmp.put_f32_le(self.yacc);
20461 __tmp.put_f32_le(self.zacc);
20462 __tmp.put_f32_le(self.xgyro);
20463 __tmp.put_f32_le(self.ygyro);
20464 __tmp.put_f32_le(self.zgyro);
20465 __tmp.put_f32_le(self.lat);
20466 __tmp.put_f32_le(self.lon);
20467 __tmp.put_f32_le(self.alt);
20468 __tmp.put_f32_le(self.std_dev_horz);
20469 __tmp.put_f32_le(self.std_dev_vert);
20470 __tmp.put_f32_le(self.vn);
20471 __tmp.put_f32_le(self.ve);
20472 __tmp.put_f32_le(self.vd);
20473 __tmp.put_i32_le(self.lat_int);
20474 __tmp.put_i32_le(self.lon_int);
20475 if matches!(version, MavlinkVersion::V2) {
20476 let len = __tmp.len();
20477 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20478 } else {
20479 __tmp.len()
20480 }
20481 }
20482}
20483#[doc = "id: 128"]
20484#[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
20485#[derive(Debug, Clone, PartialEq)]
20486#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20487#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20488pub struct GPS2_RTK_DATA {
20489 #[doc = "Time since boot of last baseline message received."]
20490 pub time_last_baseline_ms: u32,
20491 #[doc = "GPS Time of Week of last baseline"]
20492 pub tow: u32,
20493 #[doc = "Current baseline in ECEF x or NED north component."]
20494 pub baseline_a_mm: i32,
20495 #[doc = "Current baseline in ECEF y or NED east component."]
20496 pub baseline_b_mm: i32,
20497 #[doc = "Current baseline in ECEF z or NED down component."]
20498 pub baseline_c_mm: i32,
20499 #[doc = "Current estimate of baseline accuracy."]
20500 pub accuracy: u32,
20501 #[doc = "Current number of integer ambiguity hypotheses."]
20502 pub iar_num_hypotheses: i32,
20503 #[doc = "GPS Week Number of last baseline"]
20504 pub wn: u16,
20505 #[doc = "Identification of connected RTK receiver."]
20506 pub rtk_receiver_id: u8,
20507 #[doc = "GPS-specific health report for RTK data."]
20508 pub rtk_health: u8,
20509 #[doc = "Rate of baseline messages being received by GPS"]
20510 pub rtk_rate: u8,
20511 #[doc = "Current number of sats used for RTK calculation."]
20512 pub nsats: u8,
20513 #[doc = "Coordinate system of baseline"]
20514 pub baseline_coords_type: RtkBaselineCoordinateSystem,
20515}
20516impl GPS2_RTK_DATA {
20517 pub const ENCODED_LEN: usize = 35usize;
20518 pub const DEFAULT: Self = Self {
20519 time_last_baseline_ms: 0_u32,
20520 tow: 0_u32,
20521 baseline_a_mm: 0_i32,
20522 baseline_b_mm: 0_i32,
20523 baseline_c_mm: 0_i32,
20524 accuracy: 0_u32,
20525 iar_num_hypotheses: 0_i32,
20526 wn: 0_u16,
20527 rtk_receiver_id: 0_u8,
20528 rtk_health: 0_u8,
20529 rtk_rate: 0_u8,
20530 nsats: 0_u8,
20531 baseline_coords_type: RtkBaselineCoordinateSystem::DEFAULT,
20532 };
20533 #[cfg(feature = "arbitrary")]
20534 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20535 use arbitrary::{Arbitrary, Unstructured};
20536 let mut buf = [0u8; 1024];
20537 rng.fill_bytes(&mut buf);
20538 let mut unstructured = Unstructured::new(&buf);
20539 Self::arbitrary(&mut unstructured).unwrap_or_default()
20540 }
20541}
20542impl Default for GPS2_RTK_DATA {
20543 fn default() -> Self {
20544 Self::DEFAULT.clone()
20545 }
20546}
20547impl MessageData for GPS2_RTK_DATA {
20548 type Message = MavMessage;
20549 const ID: u32 = 128u32;
20550 const NAME: &'static str = "GPS2_RTK";
20551 const EXTRA_CRC: u8 = 226u8;
20552 const ENCODED_LEN: usize = 35usize;
20553 fn deser(
20554 _version: MavlinkVersion,
20555 __input: &[u8],
20556 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20557 let avail_len = __input.len();
20558 let mut payload_buf = [0; Self::ENCODED_LEN];
20559 let mut buf = if avail_len < Self::ENCODED_LEN {
20560 payload_buf[0..avail_len].copy_from_slice(__input);
20561 Bytes::new(&payload_buf)
20562 } else {
20563 Bytes::new(__input)
20564 };
20565 let mut __struct = Self::default();
20566 __struct.time_last_baseline_ms = buf.get_u32_le();
20567 __struct.tow = buf.get_u32_le();
20568 __struct.baseline_a_mm = buf.get_i32_le();
20569 __struct.baseline_b_mm = buf.get_i32_le();
20570 __struct.baseline_c_mm = buf.get_i32_le();
20571 __struct.accuracy = buf.get_u32_le();
20572 __struct.iar_num_hypotheses = buf.get_i32_le();
20573 __struct.wn = buf.get_u16_le();
20574 __struct.rtk_receiver_id = buf.get_u8();
20575 __struct.rtk_health = buf.get_u8();
20576 __struct.rtk_rate = buf.get_u8();
20577 __struct.nsats = buf.get_u8();
20578 let tmp = buf.get_u8();
20579 __struct.baseline_coords_type =
20580 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20581 enum_type: "RtkBaselineCoordinateSystem",
20582 value: tmp as u32,
20583 })?;
20584 Ok(__struct)
20585 }
20586 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20587 let mut __tmp = BytesMut::new(bytes);
20588 #[allow(clippy::absurd_extreme_comparisons)]
20589 #[allow(unused_comparisons)]
20590 if __tmp.remaining() < Self::ENCODED_LEN {
20591 panic!(
20592 "buffer is too small (need {} bytes, but got {})",
20593 Self::ENCODED_LEN,
20594 __tmp.remaining(),
20595 )
20596 }
20597 __tmp.put_u32_le(self.time_last_baseline_ms);
20598 __tmp.put_u32_le(self.tow);
20599 __tmp.put_i32_le(self.baseline_a_mm);
20600 __tmp.put_i32_le(self.baseline_b_mm);
20601 __tmp.put_i32_le(self.baseline_c_mm);
20602 __tmp.put_u32_le(self.accuracy);
20603 __tmp.put_i32_le(self.iar_num_hypotheses);
20604 __tmp.put_u16_le(self.wn);
20605 __tmp.put_u8(self.rtk_receiver_id);
20606 __tmp.put_u8(self.rtk_health);
20607 __tmp.put_u8(self.rtk_rate);
20608 __tmp.put_u8(self.nsats);
20609 __tmp.put_u8(self.baseline_coords_type as u8);
20610 if matches!(version, MavlinkVersion::V2) {
20611 let len = __tmp.len();
20612 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20613 } else {
20614 __tmp.len()
20615 }
20616 }
20617}
20618#[doc = "id: 36"]
20619#[doc = "Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%."]
20620#[derive(Debug, Clone, PartialEq)]
20621#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20622#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20623pub struct SERVO_OUTPUT_RAW_DATA {
20624 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
20625 pub time_usec: u32,
20626 #[doc = "Servo output 1 value"]
20627 pub servo1_raw: u16,
20628 #[doc = "Servo output 2 value"]
20629 pub servo2_raw: u16,
20630 #[doc = "Servo output 3 value"]
20631 pub servo3_raw: u16,
20632 #[doc = "Servo output 4 value"]
20633 pub servo4_raw: u16,
20634 #[doc = "Servo output 5 value"]
20635 pub servo5_raw: u16,
20636 #[doc = "Servo output 6 value"]
20637 pub servo6_raw: u16,
20638 #[doc = "Servo output 7 value"]
20639 pub servo7_raw: u16,
20640 #[doc = "Servo output 8 value"]
20641 pub servo8_raw: u16,
20642 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
20643 pub port: u8,
20644 #[doc = "Servo output 9 value"]
20645 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20646 pub servo9_raw: u16,
20647 #[doc = "Servo output 10 value"]
20648 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20649 pub servo10_raw: u16,
20650 #[doc = "Servo output 11 value"]
20651 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20652 pub servo11_raw: u16,
20653 #[doc = "Servo output 12 value"]
20654 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20655 pub servo12_raw: u16,
20656 #[doc = "Servo output 13 value"]
20657 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20658 pub servo13_raw: u16,
20659 #[doc = "Servo output 14 value"]
20660 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20661 pub servo14_raw: u16,
20662 #[doc = "Servo output 15 value"]
20663 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20664 pub servo15_raw: u16,
20665 #[doc = "Servo output 16 value"]
20666 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20667 pub servo16_raw: u16,
20668}
20669impl SERVO_OUTPUT_RAW_DATA {
20670 pub const ENCODED_LEN: usize = 37usize;
20671 pub const DEFAULT: Self = Self {
20672 time_usec: 0_u32,
20673 servo1_raw: 0_u16,
20674 servo2_raw: 0_u16,
20675 servo3_raw: 0_u16,
20676 servo4_raw: 0_u16,
20677 servo5_raw: 0_u16,
20678 servo6_raw: 0_u16,
20679 servo7_raw: 0_u16,
20680 servo8_raw: 0_u16,
20681 port: 0_u8,
20682 servo9_raw: 0_u16,
20683 servo10_raw: 0_u16,
20684 servo11_raw: 0_u16,
20685 servo12_raw: 0_u16,
20686 servo13_raw: 0_u16,
20687 servo14_raw: 0_u16,
20688 servo15_raw: 0_u16,
20689 servo16_raw: 0_u16,
20690 };
20691 #[cfg(feature = "arbitrary")]
20692 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20693 use arbitrary::{Arbitrary, Unstructured};
20694 let mut buf = [0u8; 1024];
20695 rng.fill_bytes(&mut buf);
20696 let mut unstructured = Unstructured::new(&buf);
20697 Self::arbitrary(&mut unstructured).unwrap_or_default()
20698 }
20699}
20700impl Default for SERVO_OUTPUT_RAW_DATA {
20701 fn default() -> Self {
20702 Self::DEFAULT.clone()
20703 }
20704}
20705impl MessageData for SERVO_OUTPUT_RAW_DATA {
20706 type Message = MavMessage;
20707 const ID: u32 = 36u32;
20708 const NAME: &'static str = "SERVO_OUTPUT_RAW";
20709 const EXTRA_CRC: u8 = 222u8;
20710 const ENCODED_LEN: usize = 37usize;
20711 fn deser(
20712 _version: MavlinkVersion,
20713 __input: &[u8],
20714 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20715 let avail_len = __input.len();
20716 let mut payload_buf = [0; Self::ENCODED_LEN];
20717 let mut buf = if avail_len < Self::ENCODED_LEN {
20718 payload_buf[0..avail_len].copy_from_slice(__input);
20719 Bytes::new(&payload_buf)
20720 } else {
20721 Bytes::new(__input)
20722 };
20723 let mut __struct = Self::default();
20724 __struct.time_usec = buf.get_u32_le();
20725 __struct.servo1_raw = buf.get_u16_le();
20726 __struct.servo2_raw = buf.get_u16_le();
20727 __struct.servo3_raw = buf.get_u16_le();
20728 __struct.servo4_raw = buf.get_u16_le();
20729 __struct.servo5_raw = buf.get_u16_le();
20730 __struct.servo6_raw = buf.get_u16_le();
20731 __struct.servo7_raw = buf.get_u16_le();
20732 __struct.servo8_raw = buf.get_u16_le();
20733 __struct.port = buf.get_u8();
20734 __struct.servo9_raw = buf.get_u16_le();
20735 __struct.servo10_raw = buf.get_u16_le();
20736 __struct.servo11_raw = buf.get_u16_le();
20737 __struct.servo12_raw = buf.get_u16_le();
20738 __struct.servo13_raw = buf.get_u16_le();
20739 __struct.servo14_raw = buf.get_u16_le();
20740 __struct.servo15_raw = buf.get_u16_le();
20741 __struct.servo16_raw = buf.get_u16_le();
20742 Ok(__struct)
20743 }
20744 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20745 let mut __tmp = BytesMut::new(bytes);
20746 #[allow(clippy::absurd_extreme_comparisons)]
20747 #[allow(unused_comparisons)]
20748 if __tmp.remaining() < Self::ENCODED_LEN {
20749 panic!(
20750 "buffer is too small (need {} bytes, but got {})",
20751 Self::ENCODED_LEN,
20752 __tmp.remaining(),
20753 )
20754 }
20755 __tmp.put_u32_le(self.time_usec);
20756 __tmp.put_u16_le(self.servo1_raw);
20757 __tmp.put_u16_le(self.servo2_raw);
20758 __tmp.put_u16_le(self.servo3_raw);
20759 __tmp.put_u16_le(self.servo4_raw);
20760 __tmp.put_u16_le(self.servo5_raw);
20761 __tmp.put_u16_le(self.servo6_raw);
20762 __tmp.put_u16_le(self.servo7_raw);
20763 __tmp.put_u16_le(self.servo8_raw);
20764 __tmp.put_u8(self.port);
20765 __tmp.put_u16_le(self.servo9_raw);
20766 __tmp.put_u16_le(self.servo10_raw);
20767 __tmp.put_u16_le(self.servo11_raw);
20768 __tmp.put_u16_le(self.servo12_raw);
20769 __tmp.put_u16_le(self.servo13_raw);
20770 __tmp.put_u16_le(self.servo14_raw);
20771 __tmp.put_u16_le(self.servo15_raw);
20772 __tmp.put_u16_le(self.servo16_raw);
20773 if matches!(version, MavlinkVersion::V2) {
20774 let len = __tmp.len();
20775 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20776 } else {
20777 __tmp.len()
20778 }
20779 }
20780}
20781#[doc = "id: 148"]
20782#[doc = "Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE."]
20783#[derive(Debug, Clone, PartialEq)]
20784#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20785#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20786pub struct AUTOPILOT_VERSION_DATA {
20787 #[doc = "Bitmap of capabilities"]
20788 pub capabilities: MavProtocolCapability,
20789 #[doc = "UID if provided by hardware (see uid2)"]
20790 pub uid: u64,
20791 #[doc = "Firmware version number. The field must be encoded as 4 bytes, where each byte (shown from MSB to LSB) is part of a semantic version: (major) (minor) (patch) (FIRMWARE_VERSION_TYPE)."]
20792 pub flight_sw_version: u32,
20793 #[doc = "Middleware version number"]
20794 pub middleware_sw_version: u32,
20795 #[doc = "Operating system version number"]
20796 pub os_sw_version: u32,
20797 #[doc = "HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify <https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt>"]
20798 pub board_version: u32,
20799 #[doc = "ID of the board vendor"]
20800 pub vendor_id: u16,
20801 #[doc = "ID of the product"]
20802 pub product_id: u16,
20803 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
20804 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20805 pub flight_custom_version: [u8; 8],
20806 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
20807 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20808 pub middleware_custom_version: [u8; 8],
20809 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
20810 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20811 pub os_custom_version: [u8; 8],
20812 #[doc = "UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)"]
20813 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20814 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20815 pub uid2: [u8; 18],
20816}
20817impl AUTOPILOT_VERSION_DATA {
20818 pub const ENCODED_LEN: usize = 78usize;
20819 pub const DEFAULT: Self = Self {
20820 capabilities: MavProtocolCapability::DEFAULT,
20821 uid: 0_u64,
20822 flight_sw_version: 0_u32,
20823 middleware_sw_version: 0_u32,
20824 os_sw_version: 0_u32,
20825 board_version: 0_u32,
20826 vendor_id: 0_u16,
20827 product_id: 0_u16,
20828 flight_custom_version: [0_u8; 8usize],
20829 middleware_custom_version: [0_u8; 8usize],
20830 os_custom_version: [0_u8; 8usize],
20831 uid2: [0_u8; 18usize],
20832 };
20833 #[cfg(feature = "arbitrary")]
20834 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20835 use arbitrary::{Arbitrary, Unstructured};
20836 let mut buf = [0u8; 1024];
20837 rng.fill_bytes(&mut buf);
20838 let mut unstructured = Unstructured::new(&buf);
20839 Self::arbitrary(&mut unstructured).unwrap_or_default()
20840 }
20841}
20842impl Default for AUTOPILOT_VERSION_DATA {
20843 fn default() -> Self {
20844 Self::DEFAULT.clone()
20845 }
20846}
20847impl MessageData for AUTOPILOT_VERSION_DATA {
20848 type Message = MavMessage;
20849 const ID: u32 = 148u32;
20850 const NAME: &'static str = "AUTOPILOT_VERSION";
20851 const EXTRA_CRC: u8 = 178u8;
20852 const ENCODED_LEN: usize = 78usize;
20853 fn deser(
20854 _version: MavlinkVersion,
20855 __input: &[u8],
20856 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20857 let avail_len = __input.len();
20858 let mut payload_buf = [0; Self::ENCODED_LEN];
20859 let mut buf = if avail_len < Self::ENCODED_LEN {
20860 payload_buf[0..avail_len].copy_from_slice(__input);
20861 Bytes::new(&payload_buf)
20862 } else {
20863 Bytes::new(__input)
20864 };
20865 let mut __struct = Self::default();
20866 let tmp = buf.get_u64_le();
20867 __struct.capabilities = MavProtocolCapability::from_bits(
20868 tmp & MavProtocolCapability::all().bits(),
20869 )
20870 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
20871 flag_type: "MavProtocolCapability",
20872 value: tmp as u32,
20873 })?;
20874 __struct.uid = buf.get_u64_le();
20875 __struct.flight_sw_version = buf.get_u32_le();
20876 __struct.middleware_sw_version = buf.get_u32_le();
20877 __struct.os_sw_version = buf.get_u32_le();
20878 __struct.board_version = buf.get_u32_le();
20879 __struct.vendor_id = buf.get_u16_le();
20880 __struct.product_id = buf.get_u16_le();
20881 for v in &mut __struct.flight_custom_version {
20882 let val = buf.get_u8();
20883 *v = val;
20884 }
20885 for v in &mut __struct.middleware_custom_version {
20886 let val = buf.get_u8();
20887 *v = val;
20888 }
20889 for v in &mut __struct.os_custom_version {
20890 let val = buf.get_u8();
20891 *v = val;
20892 }
20893 for v in &mut __struct.uid2 {
20894 let val = buf.get_u8();
20895 *v = val;
20896 }
20897 Ok(__struct)
20898 }
20899 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20900 let mut __tmp = BytesMut::new(bytes);
20901 #[allow(clippy::absurd_extreme_comparisons)]
20902 #[allow(unused_comparisons)]
20903 if __tmp.remaining() < Self::ENCODED_LEN {
20904 panic!(
20905 "buffer is too small (need {} bytes, but got {})",
20906 Self::ENCODED_LEN,
20907 __tmp.remaining(),
20908 )
20909 }
20910 __tmp.put_u64_le(self.capabilities.bits());
20911 __tmp.put_u64_le(self.uid);
20912 __tmp.put_u32_le(self.flight_sw_version);
20913 __tmp.put_u32_le(self.middleware_sw_version);
20914 __tmp.put_u32_le(self.os_sw_version);
20915 __tmp.put_u32_le(self.board_version);
20916 __tmp.put_u16_le(self.vendor_id);
20917 __tmp.put_u16_le(self.product_id);
20918 for val in &self.flight_custom_version {
20919 __tmp.put_u8(*val);
20920 }
20921 for val in &self.middleware_custom_version {
20922 __tmp.put_u8(*val);
20923 }
20924 for val in &self.os_custom_version {
20925 __tmp.put_u8(*val);
20926 }
20927 for val in &self.uid2 {
20928 __tmp.put_u8(*val);
20929 }
20930 if matches!(version, MavlinkVersion::V2) {
20931 let len = __tmp.len();
20932 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20933 } else {
20934 __tmp.len()
20935 }
20936 }
20937}
20938#[doc = "id: 310"]
20939#[doc = "General status information of an UAVCAN node. Please refer to the definition of the UAVCAN message \"uavcan.protocol.NodeStatus\" for the background information. The UAVCAN specification is available at <http://uavcan.org>."]
20940#[derive(Debug, Clone, PartialEq)]
20941#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20942#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20943pub struct UAVCAN_NODE_STATUS_DATA {
20944 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
20945 pub time_usec: u64,
20946 #[doc = "Time since the start-up of the node."]
20947 pub uptime_sec: u32,
20948 #[doc = "Vendor-specific status information."]
20949 pub vendor_specific_status_code: u16,
20950 #[doc = "Generalized node health status."]
20951 pub health: UavcanNodeHealth,
20952 #[doc = "Generalized operating mode."]
20953 pub mode: UavcanNodeMode,
20954 #[doc = "Not used currently."]
20955 pub sub_mode: u8,
20956}
20957impl UAVCAN_NODE_STATUS_DATA {
20958 pub const ENCODED_LEN: usize = 17usize;
20959 pub const DEFAULT: Self = Self {
20960 time_usec: 0_u64,
20961 uptime_sec: 0_u32,
20962 vendor_specific_status_code: 0_u16,
20963 health: UavcanNodeHealth::DEFAULT,
20964 mode: UavcanNodeMode::DEFAULT,
20965 sub_mode: 0_u8,
20966 };
20967 #[cfg(feature = "arbitrary")]
20968 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20969 use arbitrary::{Arbitrary, Unstructured};
20970 let mut buf = [0u8; 1024];
20971 rng.fill_bytes(&mut buf);
20972 let mut unstructured = Unstructured::new(&buf);
20973 Self::arbitrary(&mut unstructured).unwrap_or_default()
20974 }
20975}
20976impl Default for UAVCAN_NODE_STATUS_DATA {
20977 fn default() -> Self {
20978 Self::DEFAULT.clone()
20979 }
20980}
20981impl MessageData for UAVCAN_NODE_STATUS_DATA {
20982 type Message = MavMessage;
20983 const ID: u32 = 310u32;
20984 const NAME: &'static str = "UAVCAN_NODE_STATUS";
20985 const EXTRA_CRC: u8 = 28u8;
20986 const ENCODED_LEN: usize = 17usize;
20987 fn deser(
20988 _version: MavlinkVersion,
20989 __input: &[u8],
20990 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20991 let avail_len = __input.len();
20992 let mut payload_buf = [0; Self::ENCODED_LEN];
20993 let mut buf = if avail_len < Self::ENCODED_LEN {
20994 payload_buf[0..avail_len].copy_from_slice(__input);
20995 Bytes::new(&payload_buf)
20996 } else {
20997 Bytes::new(__input)
20998 };
20999 let mut __struct = Self::default();
21000 __struct.time_usec = buf.get_u64_le();
21001 __struct.uptime_sec = buf.get_u32_le();
21002 __struct.vendor_specific_status_code = buf.get_u16_le();
21003 let tmp = buf.get_u8();
21004 __struct.health =
21005 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21006 enum_type: "UavcanNodeHealth",
21007 value: tmp as u32,
21008 })?;
21009 let tmp = buf.get_u8();
21010 __struct.mode =
21011 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21012 enum_type: "UavcanNodeMode",
21013 value: tmp as u32,
21014 })?;
21015 __struct.sub_mode = buf.get_u8();
21016 Ok(__struct)
21017 }
21018 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21019 let mut __tmp = BytesMut::new(bytes);
21020 #[allow(clippy::absurd_extreme_comparisons)]
21021 #[allow(unused_comparisons)]
21022 if __tmp.remaining() < Self::ENCODED_LEN {
21023 panic!(
21024 "buffer is too small (need {} bytes, but got {})",
21025 Self::ENCODED_LEN,
21026 __tmp.remaining(),
21027 )
21028 }
21029 __tmp.put_u64_le(self.time_usec);
21030 __tmp.put_u32_le(self.uptime_sec);
21031 __tmp.put_u16_le(self.vendor_specific_status_code);
21032 __tmp.put_u8(self.health as u8);
21033 __tmp.put_u8(self.mode as u8);
21034 __tmp.put_u8(self.sub_mode);
21035 if matches!(version, MavlinkVersion::V2) {
21036 let len = __tmp.len();
21037 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21038 } else {
21039 __tmp.len()
21040 }
21041 }
21042}
21043#[doc = "id: 28"]
21044#[doc = "The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values."]
21045#[derive(Debug, Clone, PartialEq)]
21046#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21047#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21048pub struct RAW_PRESSURE_DATA {
21049 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
21050 pub time_usec: u64,
21051 #[doc = "Absolute pressure (raw)"]
21052 pub press_abs: i16,
21053 #[doc = "Differential pressure 1 (raw, 0 if nonexistent)"]
21054 pub press_diff1: i16,
21055 #[doc = "Differential pressure 2 (raw, 0 if nonexistent)"]
21056 pub press_diff2: i16,
21057 #[doc = "Raw Temperature measurement (raw)"]
21058 pub temperature: i16,
21059}
21060impl RAW_PRESSURE_DATA {
21061 pub const ENCODED_LEN: usize = 16usize;
21062 pub const DEFAULT: Self = Self {
21063 time_usec: 0_u64,
21064 press_abs: 0_i16,
21065 press_diff1: 0_i16,
21066 press_diff2: 0_i16,
21067 temperature: 0_i16,
21068 };
21069 #[cfg(feature = "arbitrary")]
21070 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21071 use arbitrary::{Arbitrary, Unstructured};
21072 let mut buf = [0u8; 1024];
21073 rng.fill_bytes(&mut buf);
21074 let mut unstructured = Unstructured::new(&buf);
21075 Self::arbitrary(&mut unstructured).unwrap_or_default()
21076 }
21077}
21078impl Default for RAW_PRESSURE_DATA {
21079 fn default() -> Self {
21080 Self::DEFAULT.clone()
21081 }
21082}
21083impl MessageData for RAW_PRESSURE_DATA {
21084 type Message = MavMessage;
21085 const ID: u32 = 28u32;
21086 const NAME: &'static str = "RAW_PRESSURE";
21087 const EXTRA_CRC: u8 = 67u8;
21088 const ENCODED_LEN: usize = 16usize;
21089 fn deser(
21090 _version: MavlinkVersion,
21091 __input: &[u8],
21092 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21093 let avail_len = __input.len();
21094 let mut payload_buf = [0; Self::ENCODED_LEN];
21095 let mut buf = if avail_len < Self::ENCODED_LEN {
21096 payload_buf[0..avail_len].copy_from_slice(__input);
21097 Bytes::new(&payload_buf)
21098 } else {
21099 Bytes::new(__input)
21100 };
21101 let mut __struct = Self::default();
21102 __struct.time_usec = buf.get_u64_le();
21103 __struct.press_abs = buf.get_i16_le();
21104 __struct.press_diff1 = buf.get_i16_le();
21105 __struct.press_diff2 = buf.get_i16_le();
21106 __struct.temperature = buf.get_i16_le();
21107 Ok(__struct)
21108 }
21109 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21110 let mut __tmp = BytesMut::new(bytes);
21111 #[allow(clippy::absurd_extreme_comparisons)]
21112 #[allow(unused_comparisons)]
21113 if __tmp.remaining() < Self::ENCODED_LEN {
21114 panic!(
21115 "buffer is too small (need {} bytes, but got {})",
21116 Self::ENCODED_LEN,
21117 __tmp.remaining(),
21118 )
21119 }
21120 __tmp.put_u64_le(self.time_usec);
21121 __tmp.put_i16_le(self.press_abs);
21122 __tmp.put_i16_le(self.press_diff1);
21123 __tmp.put_i16_le(self.press_diff2);
21124 __tmp.put_i16_le(self.temperature);
21125 if matches!(version, MavlinkVersion::V2) {
21126 let len = __tmp.len();
21127 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21128 } else {
21129 __tmp.len()
21130 }
21131 }
21132}
21133#[doc = "id: 270"]
21134#[doc = "Information about the status of a video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE."]
21135#[derive(Debug, Clone, PartialEq)]
21136#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21137#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21138pub struct VIDEO_STREAM_STATUS_DATA {
21139 #[doc = "Frame rate"]
21140 pub framerate: f32,
21141 #[doc = "Bit rate"]
21142 pub bitrate: u32,
21143 #[doc = "Bitmap of stream status flags"]
21144 pub flags: VideoStreamStatusFlags,
21145 #[doc = "Horizontal resolution"]
21146 pub resolution_h: u16,
21147 #[doc = "Vertical resolution"]
21148 pub resolution_v: u16,
21149 #[doc = "Video image rotation clockwise"]
21150 pub rotation: u16,
21151 #[doc = "Horizontal Field of view"]
21152 pub hfov: u16,
21153 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
21154 pub stream_id: u8,
21155 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
21156 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21157 pub camera_device_id: u8,
21158}
21159impl VIDEO_STREAM_STATUS_DATA {
21160 pub const ENCODED_LEN: usize = 20usize;
21161 pub const DEFAULT: Self = Self {
21162 framerate: 0.0_f32,
21163 bitrate: 0_u32,
21164 flags: VideoStreamStatusFlags::DEFAULT,
21165 resolution_h: 0_u16,
21166 resolution_v: 0_u16,
21167 rotation: 0_u16,
21168 hfov: 0_u16,
21169 stream_id: 0_u8,
21170 camera_device_id: 0_u8,
21171 };
21172 #[cfg(feature = "arbitrary")]
21173 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21174 use arbitrary::{Arbitrary, Unstructured};
21175 let mut buf = [0u8; 1024];
21176 rng.fill_bytes(&mut buf);
21177 let mut unstructured = Unstructured::new(&buf);
21178 Self::arbitrary(&mut unstructured).unwrap_or_default()
21179 }
21180}
21181impl Default for VIDEO_STREAM_STATUS_DATA {
21182 fn default() -> Self {
21183 Self::DEFAULT.clone()
21184 }
21185}
21186impl MessageData for VIDEO_STREAM_STATUS_DATA {
21187 type Message = MavMessage;
21188 const ID: u32 = 270u32;
21189 const NAME: &'static str = "VIDEO_STREAM_STATUS";
21190 const EXTRA_CRC: u8 = 59u8;
21191 const ENCODED_LEN: usize = 20usize;
21192 fn deser(
21193 _version: MavlinkVersion,
21194 __input: &[u8],
21195 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21196 let avail_len = __input.len();
21197 let mut payload_buf = [0; Self::ENCODED_LEN];
21198 let mut buf = if avail_len < Self::ENCODED_LEN {
21199 payload_buf[0..avail_len].copy_from_slice(__input);
21200 Bytes::new(&payload_buf)
21201 } else {
21202 Bytes::new(__input)
21203 };
21204 let mut __struct = Self::default();
21205 __struct.framerate = buf.get_f32_le();
21206 __struct.bitrate = buf.get_u32_le();
21207 let tmp = buf.get_u16_le();
21208 __struct.flags = VideoStreamStatusFlags::from_bits(
21209 tmp & VideoStreamStatusFlags::all().bits(),
21210 )
21211 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
21212 flag_type: "VideoStreamStatusFlags",
21213 value: tmp as u32,
21214 })?;
21215 __struct.resolution_h = buf.get_u16_le();
21216 __struct.resolution_v = buf.get_u16_le();
21217 __struct.rotation = buf.get_u16_le();
21218 __struct.hfov = buf.get_u16_le();
21219 __struct.stream_id = buf.get_u8();
21220 __struct.camera_device_id = buf.get_u8();
21221 Ok(__struct)
21222 }
21223 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21224 let mut __tmp = BytesMut::new(bytes);
21225 #[allow(clippy::absurd_extreme_comparisons)]
21226 #[allow(unused_comparisons)]
21227 if __tmp.remaining() < Self::ENCODED_LEN {
21228 panic!(
21229 "buffer is too small (need {} bytes, but got {})",
21230 Self::ENCODED_LEN,
21231 __tmp.remaining(),
21232 )
21233 }
21234 __tmp.put_f32_le(self.framerate);
21235 __tmp.put_u32_le(self.bitrate);
21236 __tmp.put_u16_le(self.flags.bits());
21237 __tmp.put_u16_le(self.resolution_h);
21238 __tmp.put_u16_le(self.resolution_v);
21239 __tmp.put_u16_le(self.rotation);
21240 __tmp.put_u16_le(self.hfov);
21241 __tmp.put_u8(self.stream_id);
21242 __tmp.put_u8(self.camera_device_id);
21243 if matches!(version, MavlinkVersion::V2) {
21244 let len = __tmp.len();
21245 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21246 } else {
21247 __tmp.len()
21248 }
21249 }
21250}
21251#[doc = "id: 257"]
21252#[doc = "Report button state change."]
21253#[derive(Debug, Clone, PartialEq)]
21254#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21255#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21256pub struct BUTTON_CHANGE_DATA {
21257 #[doc = "Timestamp (time since system boot)."]
21258 pub time_boot_ms: u32,
21259 #[doc = "Time of last change of button state."]
21260 pub last_change_ms: u32,
21261 #[doc = "Bitmap for state of buttons."]
21262 pub state: u8,
21263}
21264impl BUTTON_CHANGE_DATA {
21265 pub const ENCODED_LEN: usize = 9usize;
21266 pub const DEFAULT: Self = Self {
21267 time_boot_ms: 0_u32,
21268 last_change_ms: 0_u32,
21269 state: 0_u8,
21270 };
21271 #[cfg(feature = "arbitrary")]
21272 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21273 use arbitrary::{Arbitrary, Unstructured};
21274 let mut buf = [0u8; 1024];
21275 rng.fill_bytes(&mut buf);
21276 let mut unstructured = Unstructured::new(&buf);
21277 Self::arbitrary(&mut unstructured).unwrap_or_default()
21278 }
21279}
21280impl Default for BUTTON_CHANGE_DATA {
21281 fn default() -> Self {
21282 Self::DEFAULT.clone()
21283 }
21284}
21285impl MessageData for BUTTON_CHANGE_DATA {
21286 type Message = MavMessage;
21287 const ID: u32 = 257u32;
21288 const NAME: &'static str = "BUTTON_CHANGE";
21289 const EXTRA_CRC: u8 = 131u8;
21290 const ENCODED_LEN: usize = 9usize;
21291 fn deser(
21292 _version: MavlinkVersion,
21293 __input: &[u8],
21294 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21295 let avail_len = __input.len();
21296 let mut payload_buf = [0; Self::ENCODED_LEN];
21297 let mut buf = if avail_len < Self::ENCODED_LEN {
21298 payload_buf[0..avail_len].copy_from_slice(__input);
21299 Bytes::new(&payload_buf)
21300 } else {
21301 Bytes::new(__input)
21302 };
21303 let mut __struct = Self::default();
21304 __struct.time_boot_ms = buf.get_u32_le();
21305 __struct.last_change_ms = buf.get_u32_le();
21306 __struct.state = buf.get_u8();
21307 Ok(__struct)
21308 }
21309 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21310 let mut __tmp = BytesMut::new(bytes);
21311 #[allow(clippy::absurd_extreme_comparisons)]
21312 #[allow(unused_comparisons)]
21313 if __tmp.remaining() < Self::ENCODED_LEN {
21314 panic!(
21315 "buffer is too small (need {} bytes, but got {})",
21316 Self::ENCODED_LEN,
21317 __tmp.remaining(),
21318 )
21319 }
21320 __tmp.put_u32_le(self.time_boot_ms);
21321 __tmp.put_u32_le(self.last_change_ms);
21322 __tmp.put_u8(self.state);
21323 if matches!(version, MavlinkVersion::V2) {
21324 let len = __tmp.len();
21325 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21326 } else {
21327 __tmp.len()
21328 }
21329 }
21330}
21331#[doc = "id: 300"]
21332#[doc = "Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly."]
21333#[derive(Debug, Clone, PartialEq)]
21334#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21335#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21336pub struct PROTOCOL_VERSION_DATA {
21337 #[doc = "Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc."]
21338 pub version: u16,
21339 #[doc = "Minimum MAVLink version supported"]
21340 pub min_version: u16,
21341 #[doc = "Maximum MAVLink version supported (set to the same value as version by default)"]
21342 pub max_version: u16,
21343 #[doc = "The first 8 bytes (not characters printed in hex!) of the git hash."]
21344 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21345 pub spec_version_hash: [u8; 8],
21346 #[doc = "The first 8 bytes (not characters printed in hex!) of the git hash."]
21347 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21348 pub library_version_hash: [u8; 8],
21349}
21350impl PROTOCOL_VERSION_DATA {
21351 pub const ENCODED_LEN: usize = 22usize;
21352 pub const DEFAULT: Self = Self {
21353 version: 0_u16,
21354 min_version: 0_u16,
21355 max_version: 0_u16,
21356 spec_version_hash: [0_u8; 8usize],
21357 library_version_hash: [0_u8; 8usize],
21358 };
21359 #[cfg(feature = "arbitrary")]
21360 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21361 use arbitrary::{Arbitrary, Unstructured};
21362 let mut buf = [0u8; 1024];
21363 rng.fill_bytes(&mut buf);
21364 let mut unstructured = Unstructured::new(&buf);
21365 Self::arbitrary(&mut unstructured).unwrap_or_default()
21366 }
21367}
21368impl Default for PROTOCOL_VERSION_DATA {
21369 fn default() -> Self {
21370 Self::DEFAULT.clone()
21371 }
21372}
21373impl MessageData for PROTOCOL_VERSION_DATA {
21374 type Message = MavMessage;
21375 const ID: u32 = 300u32;
21376 const NAME: &'static str = "PROTOCOL_VERSION";
21377 const EXTRA_CRC: u8 = 217u8;
21378 const ENCODED_LEN: usize = 22usize;
21379 fn deser(
21380 _version: MavlinkVersion,
21381 __input: &[u8],
21382 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21383 let avail_len = __input.len();
21384 let mut payload_buf = [0; Self::ENCODED_LEN];
21385 let mut buf = if avail_len < Self::ENCODED_LEN {
21386 payload_buf[0..avail_len].copy_from_slice(__input);
21387 Bytes::new(&payload_buf)
21388 } else {
21389 Bytes::new(__input)
21390 };
21391 let mut __struct = Self::default();
21392 __struct.version = buf.get_u16_le();
21393 __struct.min_version = buf.get_u16_le();
21394 __struct.max_version = buf.get_u16_le();
21395 for v in &mut __struct.spec_version_hash {
21396 let val = buf.get_u8();
21397 *v = val;
21398 }
21399 for v in &mut __struct.library_version_hash {
21400 let val = buf.get_u8();
21401 *v = val;
21402 }
21403 Ok(__struct)
21404 }
21405 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21406 let mut __tmp = BytesMut::new(bytes);
21407 #[allow(clippy::absurd_extreme_comparisons)]
21408 #[allow(unused_comparisons)]
21409 if __tmp.remaining() < Self::ENCODED_LEN {
21410 panic!(
21411 "buffer is too small (need {} bytes, but got {})",
21412 Self::ENCODED_LEN,
21413 __tmp.remaining(),
21414 )
21415 }
21416 __tmp.put_u16_le(self.version);
21417 __tmp.put_u16_le(self.min_version);
21418 __tmp.put_u16_le(self.max_version);
21419 for val in &self.spec_version_hash {
21420 __tmp.put_u8(*val);
21421 }
21422 for val in &self.library_version_hash {
21423 __tmp.put_u8(*val);
21424 }
21425 if matches!(version, MavlinkVersion::V2) {
21426 let len = __tmp.len();
21427 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21428 } else {
21429 __tmp.len()
21430 }
21431 }
21432}
21433#[doc = "id: 132"]
21434#[doc = "Distance sensor information for an onboard rangefinder."]
21435#[derive(Debug, Clone, PartialEq)]
21436#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21437#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21438pub struct DISTANCE_SENSOR_DATA {
21439 #[doc = "Timestamp (time since system boot)."]
21440 pub time_boot_ms: u32,
21441 #[doc = "Minimum distance the sensor can measure"]
21442 pub min_distance: u16,
21443 #[doc = "Maximum distance the sensor can measure"]
21444 pub max_distance: u16,
21445 #[doc = "Current distance reading"]
21446 pub current_distance: u16,
21447 #[doc = "Type of distance sensor."]
21448 pub mavtype: MavDistanceSensor,
21449 #[doc = "Onboard ID of the sensor"]
21450 pub id: u8,
21451 #[doc = "Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270"]
21452 pub orientation: MavSensorOrientation,
21453 #[doc = "Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown."]
21454 pub covariance: u8,
21455 #[doc = "Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0."]
21456 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21457 pub horizontal_fov: f32,
21458 #[doc = "Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0."]
21459 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21460 pub vertical_fov: f32,
21461 #[doc = "Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid.\""]
21462 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21463 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21464 pub quaternion: [f32; 4],
21465 #[doc = "Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal."]
21466 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21467 pub signal_quality: u8,
21468}
21469impl DISTANCE_SENSOR_DATA {
21470 pub const ENCODED_LEN: usize = 39usize;
21471 pub const DEFAULT: Self = Self {
21472 time_boot_ms: 0_u32,
21473 min_distance: 0_u16,
21474 max_distance: 0_u16,
21475 current_distance: 0_u16,
21476 mavtype: MavDistanceSensor::DEFAULT,
21477 id: 0_u8,
21478 orientation: MavSensorOrientation::DEFAULT,
21479 covariance: 0_u8,
21480 horizontal_fov: 0.0_f32,
21481 vertical_fov: 0.0_f32,
21482 quaternion: [0.0_f32; 4usize],
21483 signal_quality: 0_u8,
21484 };
21485 #[cfg(feature = "arbitrary")]
21486 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21487 use arbitrary::{Arbitrary, Unstructured};
21488 let mut buf = [0u8; 1024];
21489 rng.fill_bytes(&mut buf);
21490 let mut unstructured = Unstructured::new(&buf);
21491 Self::arbitrary(&mut unstructured).unwrap_or_default()
21492 }
21493}
21494impl Default for DISTANCE_SENSOR_DATA {
21495 fn default() -> Self {
21496 Self::DEFAULT.clone()
21497 }
21498}
21499impl MessageData for DISTANCE_SENSOR_DATA {
21500 type Message = MavMessage;
21501 const ID: u32 = 132u32;
21502 const NAME: &'static str = "DISTANCE_SENSOR";
21503 const EXTRA_CRC: u8 = 85u8;
21504 const ENCODED_LEN: usize = 39usize;
21505 fn deser(
21506 _version: MavlinkVersion,
21507 __input: &[u8],
21508 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21509 let avail_len = __input.len();
21510 let mut payload_buf = [0; Self::ENCODED_LEN];
21511 let mut buf = if avail_len < Self::ENCODED_LEN {
21512 payload_buf[0..avail_len].copy_from_slice(__input);
21513 Bytes::new(&payload_buf)
21514 } else {
21515 Bytes::new(__input)
21516 };
21517 let mut __struct = Self::default();
21518 __struct.time_boot_ms = buf.get_u32_le();
21519 __struct.min_distance = buf.get_u16_le();
21520 __struct.max_distance = buf.get_u16_le();
21521 __struct.current_distance = buf.get_u16_le();
21522 let tmp = buf.get_u8();
21523 __struct.mavtype =
21524 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21525 enum_type: "MavDistanceSensor",
21526 value: tmp as u32,
21527 })?;
21528 __struct.id = buf.get_u8();
21529 let tmp = buf.get_u8();
21530 __struct.orientation =
21531 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21532 enum_type: "MavSensorOrientation",
21533 value: tmp as u32,
21534 })?;
21535 __struct.covariance = buf.get_u8();
21536 __struct.horizontal_fov = buf.get_f32_le();
21537 __struct.vertical_fov = buf.get_f32_le();
21538 for v in &mut __struct.quaternion {
21539 let val = buf.get_f32_le();
21540 *v = val;
21541 }
21542 __struct.signal_quality = buf.get_u8();
21543 Ok(__struct)
21544 }
21545 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21546 let mut __tmp = BytesMut::new(bytes);
21547 #[allow(clippy::absurd_extreme_comparisons)]
21548 #[allow(unused_comparisons)]
21549 if __tmp.remaining() < Self::ENCODED_LEN {
21550 panic!(
21551 "buffer is too small (need {} bytes, but got {})",
21552 Self::ENCODED_LEN,
21553 __tmp.remaining(),
21554 )
21555 }
21556 __tmp.put_u32_le(self.time_boot_ms);
21557 __tmp.put_u16_le(self.min_distance);
21558 __tmp.put_u16_le(self.max_distance);
21559 __tmp.put_u16_le(self.current_distance);
21560 __tmp.put_u8(self.mavtype as u8);
21561 __tmp.put_u8(self.id);
21562 __tmp.put_u8(self.orientation as u8);
21563 __tmp.put_u8(self.covariance);
21564 __tmp.put_f32_le(self.horizontal_fov);
21565 __tmp.put_f32_le(self.vertical_fov);
21566 for val in &self.quaternion {
21567 __tmp.put_f32_le(*val);
21568 }
21569 __tmp.put_u8(self.signal_quality);
21570 if matches!(version, MavlinkVersion::V2) {
21571 let len = __tmp.len();
21572 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21573 } else {
21574 __tmp.len()
21575 }
21576 }
21577}
21578#[doc = "id: 282"]
21579#[doc = "High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case."]
21580#[derive(Debug, Clone, PartialEq)]
21581#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21582#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21583pub struct GIMBAL_MANAGER_SET_ATTITUDE_DATA {
21584 #[doc = "High level gimbal manager flags to use."]
21585 pub flags: GimbalManagerFlags,
21586 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)"]
21587 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21588 pub q: [f32; 4],
21589 #[doc = "X component of angular velocity, positive is rolling to the right, NaN to be ignored."]
21590 pub angular_velocity_x: f32,
21591 #[doc = "Y component of angular velocity, positive is pitching up, NaN to be ignored."]
21592 pub angular_velocity_y: f32,
21593 #[doc = "Z component of angular velocity, positive is yawing to the right, NaN to be ignored."]
21594 pub angular_velocity_z: f32,
21595 #[doc = "System ID"]
21596 pub target_system: u8,
21597 #[doc = "Component ID"]
21598 pub target_component: u8,
21599 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
21600 pub gimbal_device_id: u8,
21601}
21602impl GIMBAL_MANAGER_SET_ATTITUDE_DATA {
21603 pub const ENCODED_LEN: usize = 35usize;
21604 pub const DEFAULT: Self = Self {
21605 flags: GimbalManagerFlags::DEFAULT,
21606 q: [0.0_f32; 4usize],
21607 angular_velocity_x: 0.0_f32,
21608 angular_velocity_y: 0.0_f32,
21609 angular_velocity_z: 0.0_f32,
21610 target_system: 0_u8,
21611 target_component: 0_u8,
21612 gimbal_device_id: 0_u8,
21613 };
21614 #[cfg(feature = "arbitrary")]
21615 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21616 use arbitrary::{Arbitrary, Unstructured};
21617 let mut buf = [0u8; 1024];
21618 rng.fill_bytes(&mut buf);
21619 let mut unstructured = Unstructured::new(&buf);
21620 Self::arbitrary(&mut unstructured).unwrap_or_default()
21621 }
21622}
21623impl Default for GIMBAL_MANAGER_SET_ATTITUDE_DATA {
21624 fn default() -> Self {
21625 Self::DEFAULT.clone()
21626 }
21627}
21628impl MessageData for GIMBAL_MANAGER_SET_ATTITUDE_DATA {
21629 type Message = MavMessage;
21630 const ID: u32 = 282u32;
21631 const NAME: &'static str = "GIMBAL_MANAGER_SET_ATTITUDE";
21632 const EXTRA_CRC: u8 = 123u8;
21633 const ENCODED_LEN: usize = 35usize;
21634 fn deser(
21635 _version: MavlinkVersion,
21636 __input: &[u8],
21637 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21638 let avail_len = __input.len();
21639 let mut payload_buf = [0; Self::ENCODED_LEN];
21640 let mut buf = if avail_len < Self::ENCODED_LEN {
21641 payload_buf[0..avail_len].copy_from_slice(__input);
21642 Bytes::new(&payload_buf)
21643 } else {
21644 Bytes::new(__input)
21645 };
21646 let mut __struct = Self::default();
21647 let tmp = buf.get_u32_le();
21648 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
21649 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
21650 flag_type: "GimbalManagerFlags",
21651 value: tmp as u32,
21652 })?;
21653 for v in &mut __struct.q {
21654 let val = buf.get_f32_le();
21655 *v = val;
21656 }
21657 __struct.angular_velocity_x = buf.get_f32_le();
21658 __struct.angular_velocity_y = buf.get_f32_le();
21659 __struct.angular_velocity_z = buf.get_f32_le();
21660 __struct.target_system = buf.get_u8();
21661 __struct.target_component = buf.get_u8();
21662 __struct.gimbal_device_id = buf.get_u8();
21663 Ok(__struct)
21664 }
21665 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21666 let mut __tmp = BytesMut::new(bytes);
21667 #[allow(clippy::absurd_extreme_comparisons)]
21668 #[allow(unused_comparisons)]
21669 if __tmp.remaining() < Self::ENCODED_LEN {
21670 panic!(
21671 "buffer is too small (need {} bytes, but got {})",
21672 Self::ENCODED_LEN,
21673 __tmp.remaining(),
21674 )
21675 }
21676 __tmp.put_u32_le(self.flags.bits());
21677 for val in &self.q {
21678 __tmp.put_f32_le(*val);
21679 }
21680 __tmp.put_f32_le(self.angular_velocity_x);
21681 __tmp.put_f32_le(self.angular_velocity_y);
21682 __tmp.put_f32_le(self.angular_velocity_z);
21683 __tmp.put_u8(self.target_system);
21684 __tmp.put_u8(self.target_component);
21685 __tmp.put_u8(self.gimbal_device_id);
21686 if matches!(version, MavlinkVersion::V2) {
21687 let len = __tmp.len();
21688 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21689 } else {
21690 __tmp.len()
21691 }
21692 }
21693}
21694#[doc = "id: 65"]
21695#[doc = "The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification."]
21696#[derive(Debug, Clone, PartialEq)]
21697#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21698#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21699pub struct RC_CHANNELS_DATA {
21700 #[doc = "Timestamp (time since system boot)."]
21701 pub time_boot_ms: u32,
21702 #[doc = "RC channel 1 value."]
21703 pub chan1_raw: u16,
21704 #[doc = "RC channel 2 value."]
21705 pub chan2_raw: u16,
21706 #[doc = "RC channel 3 value."]
21707 pub chan3_raw: u16,
21708 #[doc = "RC channel 4 value."]
21709 pub chan4_raw: u16,
21710 #[doc = "RC channel 5 value."]
21711 pub chan5_raw: u16,
21712 #[doc = "RC channel 6 value."]
21713 pub chan6_raw: u16,
21714 #[doc = "RC channel 7 value."]
21715 pub chan7_raw: u16,
21716 #[doc = "RC channel 8 value."]
21717 pub chan8_raw: u16,
21718 #[doc = "RC channel 9 value."]
21719 pub chan9_raw: u16,
21720 #[doc = "RC channel 10 value."]
21721 pub chan10_raw: u16,
21722 #[doc = "RC channel 11 value."]
21723 pub chan11_raw: u16,
21724 #[doc = "RC channel 12 value."]
21725 pub chan12_raw: u16,
21726 #[doc = "RC channel 13 value."]
21727 pub chan13_raw: u16,
21728 #[doc = "RC channel 14 value."]
21729 pub chan14_raw: u16,
21730 #[doc = "RC channel 15 value."]
21731 pub chan15_raw: u16,
21732 #[doc = "RC channel 16 value."]
21733 pub chan16_raw: u16,
21734 #[doc = "RC channel 17 value."]
21735 pub chan17_raw: u16,
21736 #[doc = "RC channel 18 value."]
21737 pub chan18_raw: u16,
21738 #[doc = "Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available."]
21739 pub chancount: u8,
21740 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
21741 pub rssi: u8,
21742}
21743impl RC_CHANNELS_DATA {
21744 pub const ENCODED_LEN: usize = 42usize;
21745 pub const DEFAULT: Self = Self {
21746 time_boot_ms: 0_u32,
21747 chan1_raw: 0_u16,
21748 chan2_raw: 0_u16,
21749 chan3_raw: 0_u16,
21750 chan4_raw: 0_u16,
21751 chan5_raw: 0_u16,
21752 chan6_raw: 0_u16,
21753 chan7_raw: 0_u16,
21754 chan8_raw: 0_u16,
21755 chan9_raw: 0_u16,
21756 chan10_raw: 0_u16,
21757 chan11_raw: 0_u16,
21758 chan12_raw: 0_u16,
21759 chan13_raw: 0_u16,
21760 chan14_raw: 0_u16,
21761 chan15_raw: 0_u16,
21762 chan16_raw: 0_u16,
21763 chan17_raw: 0_u16,
21764 chan18_raw: 0_u16,
21765 chancount: 0_u8,
21766 rssi: 0_u8,
21767 };
21768 #[cfg(feature = "arbitrary")]
21769 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21770 use arbitrary::{Arbitrary, Unstructured};
21771 let mut buf = [0u8; 1024];
21772 rng.fill_bytes(&mut buf);
21773 let mut unstructured = Unstructured::new(&buf);
21774 Self::arbitrary(&mut unstructured).unwrap_or_default()
21775 }
21776}
21777impl Default for RC_CHANNELS_DATA {
21778 fn default() -> Self {
21779 Self::DEFAULT.clone()
21780 }
21781}
21782impl MessageData for RC_CHANNELS_DATA {
21783 type Message = MavMessage;
21784 const ID: u32 = 65u32;
21785 const NAME: &'static str = "RC_CHANNELS";
21786 const EXTRA_CRC: u8 = 118u8;
21787 const ENCODED_LEN: usize = 42usize;
21788 fn deser(
21789 _version: MavlinkVersion,
21790 __input: &[u8],
21791 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21792 let avail_len = __input.len();
21793 let mut payload_buf = [0; Self::ENCODED_LEN];
21794 let mut buf = if avail_len < Self::ENCODED_LEN {
21795 payload_buf[0..avail_len].copy_from_slice(__input);
21796 Bytes::new(&payload_buf)
21797 } else {
21798 Bytes::new(__input)
21799 };
21800 let mut __struct = Self::default();
21801 __struct.time_boot_ms = buf.get_u32_le();
21802 __struct.chan1_raw = buf.get_u16_le();
21803 __struct.chan2_raw = buf.get_u16_le();
21804 __struct.chan3_raw = buf.get_u16_le();
21805 __struct.chan4_raw = buf.get_u16_le();
21806 __struct.chan5_raw = buf.get_u16_le();
21807 __struct.chan6_raw = buf.get_u16_le();
21808 __struct.chan7_raw = buf.get_u16_le();
21809 __struct.chan8_raw = buf.get_u16_le();
21810 __struct.chan9_raw = buf.get_u16_le();
21811 __struct.chan10_raw = buf.get_u16_le();
21812 __struct.chan11_raw = buf.get_u16_le();
21813 __struct.chan12_raw = buf.get_u16_le();
21814 __struct.chan13_raw = buf.get_u16_le();
21815 __struct.chan14_raw = buf.get_u16_le();
21816 __struct.chan15_raw = buf.get_u16_le();
21817 __struct.chan16_raw = buf.get_u16_le();
21818 __struct.chan17_raw = buf.get_u16_le();
21819 __struct.chan18_raw = buf.get_u16_le();
21820 __struct.chancount = buf.get_u8();
21821 __struct.rssi = buf.get_u8();
21822 Ok(__struct)
21823 }
21824 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21825 let mut __tmp = BytesMut::new(bytes);
21826 #[allow(clippy::absurd_extreme_comparisons)]
21827 #[allow(unused_comparisons)]
21828 if __tmp.remaining() < Self::ENCODED_LEN {
21829 panic!(
21830 "buffer is too small (need {} bytes, but got {})",
21831 Self::ENCODED_LEN,
21832 __tmp.remaining(),
21833 )
21834 }
21835 __tmp.put_u32_le(self.time_boot_ms);
21836 __tmp.put_u16_le(self.chan1_raw);
21837 __tmp.put_u16_le(self.chan2_raw);
21838 __tmp.put_u16_le(self.chan3_raw);
21839 __tmp.put_u16_le(self.chan4_raw);
21840 __tmp.put_u16_le(self.chan5_raw);
21841 __tmp.put_u16_le(self.chan6_raw);
21842 __tmp.put_u16_le(self.chan7_raw);
21843 __tmp.put_u16_le(self.chan8_raw);
21844 __tmp.put_u16_le(self.chan9_raw);
21845 __tmp.put_u16_le(self.chan10_raw);
21846 __tmp.put_u16_le(self.chan11_raw);
21847 __tmp.put_u16_le(self.chan12_raw);
21848 __tmp.put_u16_le(self.chan13_raw);
21849 __tmp.put_u16_le(self.chan14_raw);
21850 __tmp.put_u16_le(self.chan15_raw);
21851 __tmp.put_u16_le(self.chan16_raw);
21852 __tmp.put_u16_le(self.chan17_raw);
21853 __tmp.put_u16_le(self.chan18_raw);
21854 __tmp.put_u8(self.chancount);
21855 __tmp.put_u8(self.rssi);
21856 if matches!(version, MavlinkVersion::V2) {
21857 let len = __tmp.len();
21858 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21859 } else {
21860 __tmp.len()
21861 }
21862 }
21863}
21864#[doc = "id: 12919"]
21865#[doc = "Update the data in the OPEN_DRONE_ID_SYSTEM message with new location information. This can be sent to update the location information for the operator when no other information in the SYSTEM message has changed. This message allows for efficient operation on radio links which have limited uplink bandwidth while meeting requirements for update frequency of the operator location."]
21866#[derive(Debug, Clone, PartialEq)]
21867#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21868#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21869pub struct OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
21870 #[doc = "Latitude of the operator. If unknown: 0 (both Lat/Lon)."]
21871 pub operator_latitude: i32,
21872 #[doc = "Longitude of the operator. If unknown: 0 (both Lat/Lon)."]
21873 pub operator_longitude: i32,
21874 #[doc = "Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m."]
21875 pub operator_altitude_geo: f32,
21876 #[doc = "32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
21877 pub timestamp: u32,
21878 #[doc = "System ID (0 for broadcast)."]
21879 pub target_system: u8,
21880 #[doc = "Component ID (0 for broadcast)."]
21881 pub target_component: u8,
21882}
21883impl OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
21884 pub const ENCODED_LEN: usize = 18usize;
21885 pub const DEFAULT: Self = Self {
21886 operator_latitude: 0_i32,
21887 operator_longitude: 0_i32,
21888 operator_altitude_geo: 0.0_f32,
21889 timestamp: 0_u32,
21890 target_system: 0_u8,
21891 target_component: 0_u8,
21892 };
21893 #[cfg(feature = "arbitrary")]
21894 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21895 use arbitrary::{Arbitrary, Unstructured};
21896 let mut buf = [0u8; 1024];
21897 rng.fill_bytes(&mut buf);
21898 let mut unstructured = Unstructured::new(&buf);
21899 Self::arbitrary(&mut unstructured).unwrap_or_default()
21900 }
21901}
21902impl Default for OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
21903 fn default() -> Self {
21904 Self::DEFAULT.clone()
21905 }
21906}
21907impl MessageData for OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
21908 type Message = MavMessage;
21909 const ID: u32 = 12919u32;
21910 const NAME: &'static str = "OPEN_DRONE_ID_SYSTEM_UPDATE";
21911 const EXTRA_CRC: u8 = 7u8;
21912 const ENCODED_LEN: usize = 18usize;
21913 fn deser(
21914 _version: MavlinkVersion,
21915 __input: &[u8],
21916 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21917 let avail_len = __input.len();
21918 let mut payload_buf = [0; Self::ENCODED_LEN];
21919 let mut buf = if avail_len < Self::ENCODED_LEN {
21920 payload_buf[0..avail_len].copy_from_slice(__input);
21921 Bytes::new(&payload_buf)
21922 } else {
21923 Bytes::new(__input)
21924 };
21925 let mut __struct = Self::default();
21926 __struct.operator_latitude = buf.get_i32_le();
21927 __struct.operator_longitude = buf.get_i32_le();
21928 __struct.operator_altitude_geo = buf.get_f32_le();
21929 __struct.timestamp = buf.get_u32_le();
21930 __struct.target_system = buf.get_u8();
21931 __struct.target_component = buf.get_u8();
21932 Ok(__struct)
21933 }
21934 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21935 let mut __tmp = BytesMut::new(bytes);
21936 #[allow(clippy::absurd_extreme_comparisons)]
21937 #[allow(unused_comparisons)]
21938 if __tmp.remaining() < Self::ENCODED_LEN {
21939 panic!(
21940 "buffer is too small (need {} bytes, but got {})",
21941 Self::ENCODED_LEN,
21942 __tmp.remaining(),
21943 )
21944 }
21945 __tmp.put_i32_le(self.operator_latitude);
21946 __tmp.put_i32_le(self.operator_longitude);
21947 __tmp.put_f32_le(self.operator_altitude_geo);
21948 __tmp.put_u32_le(self.timestamp);
21949 __tmp.put_u8(self.target_system);
21950 __tmp.put_u8(self.target_component);
21951 if matches!(version, MavlinkVersion::V2) {
21952 let len = __tmp.len();
21953 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21954 } else {
21955 __tmp.len()
21956 }
21957 }
21958}
21959#[doc = "id: 31"]
21960#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)."]
21961#[derive(Debug, Clone, PartialEq)]
21962#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21963#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21964pub struct ATTITUDE_QUATERNION_DATA {
21965 #[doc = "Timestamp (time since system boot)."]
21966 pub time_boot_ms: u32,
21967 #[doc = "Quaternion component 1, w (1 in null-rotation)"]
21968 pub q1: f32,
21969 #[doc = "Quaternion component 2, x (0 in null-rotation)"]
21970 pub q2: f32,
21971 #[doc = "Quaternion component 3, y (0 in null-rotation)"]
21972 pub q3: f32,
21973 #[doc = "Quaternion component 4, z (0 in null-rotation)"]
21974 pub q4: f32,
21975 #[doc = "Roll angular speed"]
21976 pub rollspeed: f32,
21977 #[doc = "Pitch angular speed"]
21978 pub pitchspeed: f32,
21979 #[doc = "Yaw angular speed"]
21980 pub yawspeed: f32,
21981 #[doc = "Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode."]
21982 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21983 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21984 pub repr_offset_q: [f32; 4],
21985}
21986impl ATTITUDE_QUATERNION_DATA {
21987 pub const ENCODED_LEN: usize = 48usize;
21988 pub const DEFAULT: Self = Self {
21989 time_boot_ms: 0_u32,
21990 q1: 0.0_f32,
21991 q2: 0.0_f32,
21992 q3: 0.0_f32,
21993 q4: 0.0_f32,
21994 rollspeed: 0.0_f32,
21995 pitchspeed: 0.0_f32,
21996 yawspeed: 0.0_f32,
21997 repr_offset_q: [0.0_f32; 4usize],
21998 };
21999 #[cfg(feature = "arbitrary")]
22000 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22001 use arbitrary::{Arbitrary, Unstructured};
22002 let mut buf = [0u8; 1024];
22003 rng.fill_bytes(&mut buf);
22004 let mut unstructured = Unstructured::new(&buf);
22005 Self::arbitrary(&mut unstructured).unwrap_or_default()
22006 }
22007}
22008impl Default for ATTITUDE_QUATERNION_DATA {
22009 fn default() -> Self {
22010 Self::DEFAULT.clone()
22011 }
22012}
22013impl MessageData for ATTITUDE_QUATERNION_DATA {
22014 type Message = MavMessage;
22015 const ID: u32 = 31u32;
22016 const NAME: &'static str = "ATTITUDE_QUATERNION";
22017 const EXTRA_CRC: u8 = 246u8;
22018 const ENCODED_LEN: usize = 48usize;
22019 fn deser(
22020 _version: MavlinkVersion,
22021 __input: &[u8],
22022 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22023 let avail_len = __input.len();
22024 let mut payload_buf = [0; Self::ENCODED_LEN];
22025 let mut buf = if avail_len < Self::ENCODED_LEN {
22026 payload_buf[0..avail_len].copy_from_slice(__input);
22027 Bytes::new(&payload_buf)
22028 } else {
22029 Bytes::new(__input)
22030 };
22031 let mut __struct = Self::default();
22032 __struct.time_boot_ms = buf.get_u32_le();
22033 __struct.q1 = buf.get_f32_le();
22034 __struct.q2 = buf.get_f32_le();
22035 __struct.q3 = buf.get_f32_le();
22036 __struct.q4 = buf.get_f32_le();
22037 __struct.rollspeed = buf.get_f32_le();
22038 __struct.pitchspeed = buf.get_f32_le();
22039 __struct.yawspeed = buf.get_f32_le();
22040 for v in &mut __struct.repr_offset_q {
22041 let val = buf.get_f32_le();
22042 *v = val;
22043 }
22044 Ok(__struct)
22045 }
22046 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22047 let mut __tmp = BytesMut::new(bytes);
22048 #[allow(clippy::absurd_extreme_comparisons)]
22049 #[allow(unused_comparisons)]
22050 if __tmp.remaining() < Self::ENCODED_LEN {
22051 panic!(
22052 "buffer is too small (need {} bytes, but got {})",
22053 Self::ENCODED_LEN,
22054 __tmp.remaining(),
22055 )
22056 }
22057 __tmp.put_u32_le(self.time_boot_ms);
22058 __tmp.put_f32_le(self.q1);
22059 __tmp.put_f32_le(self.q2);
22060 __tmp.put_f32_le(self.q3);
22061 __tmp.put_f32_le(self.q4);
22062 __tmp.put_f32_le(self.rollspeed);
22063 __tmp.put_f32_le(self.pitchspeed);
22064 __tmp.put_f32_le(self.yawspeed);
22065 for val in &self.repr_offset_q {
22066 __tmp.put_f32_le(*val);
22067 }
22068 if matches!(version, MavlinkVersion::V2) {
22069 let len = __tmp.len();
22070 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22071 } else {
22072 __tmp.len()
22073 }
22074 }
22075}
22076#[doc = "id: 20"]
22077#[doc = "value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also <https://mavlink.io/en/services/parameter.html> for a full documentation of QGroundControl and IMU code."]
22078#[derive(Debug, Clone, PartialEq)]
22079#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22080#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22081pub struct PARAM_REQUEST_READ_DATA {
22082 #[doc = "Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)"]
22083 pub param_index: i16,
22084 #[doc = "System ID"]
22085 pub target_system: u8,
22086 #[doc = "Component ID"]
22087 pub target_component: u8,
22088 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
22089 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22090 pub param_id: [u8; 16],
22091}
22092impl PARAM_REQUEST_READ_DATA {
22093 pub const ENCODED_LEN: usize = 20usize;
22094 pub const DEFAULT: Self = Self {
22095 param_index: 0_i16,
22096 target_system: 0_u8,
22097 target_component: 0_u8,
22098 param_id: [0_u8; 16usize],
22099 };
22100 #[cfg(feature = "arbitrary")]
22101 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22102 use arbitrary::{Arbitrary, Unstructured};
22103 let mut buf = [0u8; 1024];
22104 rng.fill_bytes(&mut buf);
22105 let mut unstructured = Unstructured::new(&buf);
22106 Self::arbitrary(&mut unstructured).unwrap_or_default()
22107 }
22108}
22109impl Default for PARAM_REQUEST_READ_DATA {
22110 fn default() -> Self {
22111 Self::DEFAULT.clone()
22112 }
22113}
22114impl MessageData for PARAM_REQUEST_READ_DATA {
22115 type Message = MavMessage;
22116 const ID: u32 = 20u32;
22117 const NAME: &'static str = "PARAM_REQUEST_READ";
22118 const EXTRA_CRC: u8 = 214u8;
22119 const ENCODED_LEN: usize = 20usize;
22120 fn deser(
22121 _version: MavlinkVersion,
22122 __input: &[u8],
22123 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22124 let avail_len = __input.len();
22125 let mut payload_buf = [0; Self::ENCODED_LEN];
22126 let mut buf = if avail_len < Self::ENCODED_LEN {
22127 payload_buf[0..avail_len].copy_from_slice(__input);
22128 Bytes::new(&payload_buf)
22129 } else {
22130 Bytes::new(__input)
22131 };
22132 let mut __struct = Self::default();
22133 __struct.param_index = buf.get_i16_le();
22134 __struct.target_system = buf.get_u8();
22135 __struct.target_component = buf.get_u8();
22136 for v in &mut __struct.param_id {
22137 let val = buf.get_u8();
22138 *v = val;
22139 }
22140 Ok(__struct)
22141 }
22142 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22143 let mut __tmp = BytesMut::new(bytes);
22144 #[allow(clippy::absurd_extreme_comparisons)]
22145 #[allow(unused_comparisons)]
22146 if __tmp.remaining() < Self::ENCODED_LEN {
22147 panic!(
22148 "buffer is too small (need {} bytes, but got {})",
22149 Self::ENCODED_LEN,
22150 __tmp.remaining(),
22151 )
22152 }
22153 __tmp.put_i16_le(self.param_index);
22154 __tmp.put_u8(self.target_system);
22155 __tmp.put_u8(self.target_component);
22156 for val in &self.param_id {
22157 __tmp.put_u8(*val);
22158 }
22159 if matches!(version, MavlinkVersion::V2) {
22160 let len = __tmp.len();
22161 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22162 } else {
22163 __tmp.len()
22164 }
22165 }
22166}
22167#[doc = "id: 143"]
22168#[doc = "Barometer readings for 3rd barometer."]
22169#[derive(Debug, Clone, PartialEq)]
22170#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22171#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22172pub struct SCALED_PRESSURE3_DATA {
22173 #[doc = "Timestamp (time since system boot)."]
22174 pub time_boot_ms: u32,
22175 #[doc = "Absolute pressure"]
22176 pub press_abs: f32,
22177 #[doc = "Differential pressure"]
22178 pub press_diff: f32,
22179 #[doc = "Absolute pressure temperature"]
22180 pub temperature: i16,
22181 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
22182 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22183 pub temperature_press_diff: i16,
22184}
22185impl SCALED_PRESSURE3_DATA {
22186 pub const ENCODED_LEN: usize = 16usize;
22187 pub const DEFAULT: Self = Self {
22188 time_boot_ms: 0_u32,
22189 press_abs: 0.0_f32,
22190 press_diff: 0.0_f32,
22191 temperature: 0_i16,
22192 temperature_press_diff: 0_i16,
22193 };
22194 #[cfg(feature = "arbitrary")]
22195 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22196 use arbitrary::{Arbitrary, Unstructured};
22197 let mut buf = [0u8; 1024];
22198 rng.fill_bytes(&mut buf);
22199 let mut unstructured = Unstructured::new(&buf);
22200 Self::arbitrary(&mut unstructured).unwrap_or_default()
22201 }
22202}
22203impl Default for SCALED_PRESSURE3_DATA {
22204 fn default() -> Self {
22205 Self::DEFAULT.clone()
22206 }
22207}
22208impl MessageData for SCALED_PRESSURE3_DATA {
22209 type Message = MavMessage;
22210 const ID: u32 = 143u32;
22211 const NAME: &'static str = "SCALED_PRESSURE3";
22212 const EXTRA_CRC: u8 = 131u8;
22213 const ENCODED_LEN: usize = 16usize;
22214 fn deser(
22215 _version: MavlinkVersion,
22216 __input: &[u8],
22217 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22218 let avail_len = __input.len();
22219 let mut payload_buf = [0; Self::ENCODED_LEN];
22220 let mut buf = if avail_len < Self::ENCODED_LEN {
22221 payload_buf[0..avail_len].copy_from_slice(__input);
22222 Bytes::new(&payload_buf)
22223 } else {
22224 Bytes::new(__input)
22225 };
22226 let mut __struct = Self::default();
22227 __struct.time_boot_ms = buf.get_u32_le();
22228 __struct.press_abs = buf.get_f32_le();
22229 __struct.press_diff = buf.get_f32_le();
22230 __struct.temperature = buf.get_i16_le();
22231 __struct.temperature_press_diff = buf.get_i16_le();
22232 Ok(__struct)
22233 }
22234 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22235 let mut __tmp = BytesMut::new(bytes);
22236 #[allow(clippy::absurd_extreme_comparisons)]
22237 #[allow(unused_comparisons)]
22238 if __tmp.remaining() < Self::ENCODED_LEN {
22239 panic!(
22240 "buffer is too small (need {} bytes, but got {})",
22241 Self::ENCODED_LEN,
22242 __tmp.remaining(),
22243 )
22244 }
22245 __tmp.put_u32_le(self.time_boot_ms);
22246 __tmp.put_f32_le(self.press_abs);
22247 __tmp.put_f32_le(self.press_diff);
22248 __tmp.put_i16_le(self.temperature);
22249 __tmp.put_i16_le(self.temperature_press_diff);
22250 if matches!(version, MavlinkVersion::V2) {
22251 let len = __tmp.len();
22252 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22253 } else {
22254 __tmp.len()
22255 }
22256 }
22257}
22258#[doc = "id: 280"]
22259#[doc = "Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE."]
22260#[derive(Debug, Clone, PartialEq)]
22261#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22262#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22263pub struct GIMBAL_MANAGER_INFORMATION_DATA {
22264 #[doc = "Timestamp (time since system boot)."]
22265 pub time_boot_ms: u32,
22266 #[doc = "Bitmap of gimbal capability flags."]
22267 pub cap_flags: GimbalManagerCapFlags,
22268 #[doc = "Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)"]
22269 pub roll_min: f32,
22270 #[doc = "Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)"]
22271 pub roll_max: f32,
22272 #[doc = "Minimum pitch angle (positive: up, negative: down)"]
22273 pub pitch_min: f32,
22274 #[doc = "Maximum pitch angle (positive: up, negative: down)"]
22275 pub pitch_max: f32,
22276 #[doc = "Minimum yaw angle (positive: to the right, negative: to the left)"]
22277 pub yaw_min: f32,
22278 #[doc = "Maximum yaw angle (positive: to the right, negative: to the left)"]
22279 pub yaw_max: f32,
22280 #[doc = "Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal)."]
22281 pub gimbal_device_id: u8,
22282}
22283impl GIMBAL_MANAGER_INFORMATION_DATA {
22284 pub const ENCODED_LEN: usize = 33usize;
22285 pub const DEFAULT: Self = Self {
22286 time_boot_ms: 0_u32,
22287 cap_flags: GimbalManagerCapFlags::DEFAULT,
22288 roll_min: 0.0_f32,
22289 roll_max: 0.0_f32,
22290 pitch_min: 0.0_f32,
22291 pitch_max: 0.0_f32,
22292 yaw_min: 0.0_f32,
22293 yaw_max: 0.0_f32,
22294 gimbal_device_id: 0_u8,
22295 };
22296 #[cfg(feature = "arbitrary")]
22297 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22298 use arbitrary::{Arbitrary, Unstructured};
22299 let mut buf = [0u8; 1024];
22300 rng.fill_bytes(&mut buf);
22301 let mut unstructured = Unstructured::new(&buf);
22302 Self::arbitrary(&mut unstructured).unwrap_or_default()
22303 }
22304}
22305impl Default for GIMBAL_MANAGER_INFORMATION_DATA {
22306 fn default() -> Self {
22307 Self::DEFAULT.clone()
22308 }
22309}
22310impl MessageData for GIMBAL_MANAGER_INFORMATION_DATA {
22311 type Message = MavMessage;
22312 const ID: u32 = 280u32;
22313 const NAME: &'static str = "GIMBAL_MANAGER_INFORMATION";
22314 const EXTRA_CRC: u8 = 70u8;
22315 const ENCODED_LEN: usize = 33usize;
22316 fn deser(
22317 _version: MavlinkVersion,
22318 __input: &[u8],
22319 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22320 let avail_len = __input.len();
22321 let mut payload_buf = [0; Self::ENCODED_LEN];
22322 let mut buf = if avail_len < Self::ENCODED_LEN {
22323 payload_buf[0..avail_len].copy_from_slice(__input);
22324 Bytes::new(&payload_buf)
22325 } else {
22326 Bytes::new(__input)
22327 };
22328 let mut __struct = Self::default();
22329 __struct.time_boot_ms = buf.get_u32_le();
22330 let tmp = buf.get_u32_le();
22331 __struct.cap_flags = GimbalManagerCapFlags::from_bits(
22332 tmp & GimbalManagerCapFlags::all().bits(),
22333 )
22334 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22335 flag_type: "GimbalManagerCapFlags",
22336 value: tmp as u32,
22337 })?;
22338 __struct.roll_min = buf.get_f32_le();
22339 __struct.roll_max = buf.get_f32_le();
22340 __struct.pitch_min = buf.get_f32_le();
22341 __struct.pitch_max = buf.get_f32_le();
22342 __struct.yaw_min = buf.get_f32_le();
22343 __struct.yaw_max = buf.get_f32_le();
22344 __struct.gimbal_device_id = buf.get_u8();
22345 Ok(__struct)
22346 }
22347 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22348 let mut __tmp = BytesMut::new(bytes);
22349 #[allow(clippy::absurd_extreme_comparisons)]
22350 #[allow(unused_comparisons)]
22351 if __tmp.remaining() < Self::ENCODED_LEN {
22352 panic!(
22353 "buffer is too small (need {} bytes, but got {})",
22354 Self::ENCODED_LEN,
22355 __tmp.remaining(),
22356 )
22357 }
22358 __tmp.put_u32_le(self.time_boot_ms);
22359 __tmp.put_u32_le(self.cap_flags.bits());
22360 __tmp.put_f32_le(self.roll_min);
22361 __tmp.put_f32_le(self.roll_max);
22362 __tmp.put_f32_le(self.pitch_min);
22363 __tmp.put_f32_le(self.pitch_max);
22364 __tmp.put_f32_le(self.yaw_min);
22365 __tmp.put_f32_le(self.yaw_max);
22366 __tmp.put_u8(self.gimbal_device_id);
22367 if matches!(version, MavlinkVersion::V2) {
22368 let len = __tmp.len();
22369 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22370 } else {
22371 __tmp.len()
22372 }
22373 }
22374}
22375#[doc = "id: 256"]
22376#[doc = "Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing."]
22377#[derive(Debug, Clone, PartialEq)]
22378#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22379#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22380pub struct SETUP_SIGNING_DATA {
22381 #[doc = "initial timestamp"]
22382 pub initial_timestamp: u64,
22383 #[doc = "system id of the target"]
22384 pub target_system: u8,
22385 #[doc = "component ID of the target"]
22386 pub target_component: u8,
22387 #[doc = "signing key"]
22388 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22389 pub secret_key: [u8; 32],
22390}
22391impl SETUP_SIGNING_DATA {
22392 pub const ENCODED_LEN: usize = 42usize;
22393 pub const DEFAULT: Self = Self {
22394 initial_timestamp: 0_u64,
22395 target_system: 0_u8,
22396 target_component: 0_u8,
22397 secret_key: [0_u8; 32usize],
22398 };
22399 #[cfg(feature = "arbitrary")]
22400 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22401 use arbitrary::{Arbitrary, Unstructured};
22402 let mut buf = [0u8; 1024];
22403 rng.fill_bytes(&mut buf);
22404 let mut unstructured = Unstructured::new(&buf);
22405 Self::arbitrary(&mut unstructured).unwrap_or_default()
22406 }
22407}
22408impl Default for SETUP_SIGNING_DATA {
22409 fn default() -> Self {
22410 Self::DEFAULT.clone()
22411 }
22412}
22413impl MessageData for SETUP_SIGNING_DATA {
22414 type Message = MavMessage;
22415 const ID: u32 = 256u32;
22416 const NAME: &'static str = "SETUP_SIGNING";
22417 const EXTRA_CRC: u8 = 71u8;
22418 const ENCODED_LEN: usize = 42usize;
22419 fn deser(
22420 _version: MavlinkVersion,
22421 __input: &[u8],
22422 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22423 let avail_len = __input.len();
22424 let mut payload_buf = [0; Self::ENCODED_LEN];
22425 let mut buf = if avail_len < Self::ENCODED_LEN {
22426 payload_buf[0..avail_len].copy_from_slice(__input);
22427 Bytes::new(&payload_buf)
22428 } else {
22429 Bytes::new(__input)
22430 };
22431 let mut __struct = Self::default();
22432 __struct.initial_timestamp = buf.get_u64_le();
22433 __struct.target_system = buf.get_u8();
22434 __struct.target_component = buf.get_u8();
22435 for v in &mut __struct.secret_key {
22436 let val = buf.get_u8();
22437 *v = val;
22438 }
22439 Ok(__struct)
22440 }
22441 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22442 let mut __tmp = BytesMut::new(bytes);
22443 #[allow(clippy::absurd_extreme_comparisons)]
22444 #[allow(unused_comparisons)]
22445 if __tmp.remaining() < Self::ENCODED_LEN {
22446 panic!(
22447 "buffer is too small (need {} bytes, but got {})",
22448 Self::ENCODED_LEN,
22449 __tmp.remaining(),
22450 )
22451 }
22452 __tmp.put_u64_le(self.initial_timestamp);
22453 __tmp.put_u8(self.target_system);
22454 __tmp.put_u8(self.target_component);
22455 for val in &self.secret_key {
22456 __tmp.put_u8(*val);
22457 }
22458 if matches!(version, MavlinkVersion::V2) {
22459 let len = __tmp.len();
22460 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22461 } else {
22462 __tmp.len()
22463 }
22464 }
22465}
22466#[doc = "id: 119"]
22467#[doc = "Request a chunk of a log."]
22468#[derive(Debug, Clone, PartialEq)]
22469#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22470#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22471pub struct LOG_REQUEST_DATA_DATA {
22472 #[doc = "Offset into the log"]
22473 pub ofs: u32,
22474 #[doc = "Number of bytes"]
22475 pub count: u32,
22476 #[doc = "Log id (from LOG_ENTRY reply)"]
22477 pub id: u16,
22478 #[doc = "System ID"]
22479 pub target_system: u8,
22480 #[doc = "Component ID"]
22481 pub target_component: u8,
22482}
22483impl LOG_REQUEST_DATA_DATA {
22484 pub const ENCODED_LEN: usize = 12usize;
22485 pub const DEFAULT: Self = Self {
22486 ofs: 0_u32,
22487 count: 0_u32,
22488 id: 0_u16,
22489 target_system: 0_u8,
22490 target_component: 0_u8,
22491 };
22492 #[cfg(feature = "arbitrary")]
22493 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22494 use arbitrary::{Arbitrary, Unstructured};
22495 let mut buf = [0u8; 1024];
22496 rng.fill_bytes(&mut buf);
22497 let mut unstructured = Unstructured::new(&buf);
22498 Self::arbitrary(&mut unstructured).unwrap_or_default()
22499 }
22500}
22501impl Default for LOG_REQUEST_DATA_DATA {
22502 fn default() -> Self {
22503 Self::DEFAULT.clone()
22504 }
22505}
22506impl MessageData for LOG_REQUEST_DATA_DATA {
22507 type Message = MavMessage;
22508 const ID: u32 = 119u32;
22509 const NAME: &'static str = "LOG_REQUEST_DATA";
22510 const EXTRA_CRC: u8 = 116u8;
22511 const ENCODED_LEN: usize = 12usize;
22512 fn deser(
22513 _version: MavlinkVersion,
22514 __input: &[u8],
22515 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22516 let avail_len = __input.len();
22517 let mut payload_buf = [0; Self::ENCODED_LEN];
22518 let mut buf = if avail_len < Self::ENCODED_LEN {
22519 payload_buf[0..avail_len].copy_from_slice(__input);
22520 Bytes::new(&payload_buf)
22521 } else {
22522 Bytes::new(__input)
22523 };
22524 let mut __struct = Self::default();
22525 __struct.ofs = buf.get_u32_le();
22526 __struct.count = buf.get_u32_le();
22527 __struct.id = buf.get_u16_le();
22528 __struct.target_system = buf.get_u8();
22529 __struct.target_component = buf.get_u8();
22530 Ok(__struct)
22531 }
22532 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22533 let mut __tmp = BytesMut::new(bytes);
22534 #[allow(clippy::absurd_extreme_comparisons)]
22535 #[allow(unused_comparisons)]
22536 if __tmp.remaining() < Self::ENCODED_LEN {
22537 panic!(
22538 "buffer is too small (need {} bytes, but got {})",
22539 Self::ENCODED_LEN,
22540 __tmp.remaining(),
22541 )
22542 }
22543 __tmp.put_u32_le(self.ofs);
22544 __tmp.put_u32_le(self.count);
22545 __tmp.put_u16_le(self.id);
22546 __tmp.put_u8(self.target_system);
22547 __tmp.put_u8(self.target_component);
22548 if matches!(version, MavlinkVersion::V2) {
22549 let len = __tmp.len();
22550 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22551 } else {
22552 __tmp.len()
22553 }
22554 }
22555}
22556#[doc = "id: 10007"]
22557#[doc = "Control message with all data sent in UCP control message."]
22558#[derive(Debug, Clone, PartialEq)]
22559#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22560#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22561pub struct UAVIONIX_ADSB_OUT_CONTROL_DATA {
22562 #[doc = "Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX"]
22563 pub baroAltMSL: i32,
22564 #[doc = "Mode A code (typically 1200 [0x04B0] for VFR)"]
22565 pub squawk: u16,
22566 #[doc = "ADS-B transponder control state flags"]
22567 pub state: UavionixAdsbOutControlState,
22568 #[doc = "Emergency status"]
22569 pub emergencyStatus: UavionixAdsbEmergencyStatus,
22570 #[doc = "Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable."]
22571 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22572 pub flight_id: [u8; 8],
22573 #[doc = "X-Bit enable (military transponders only)"]
22574 pub x_bit: UavionixAdsbXbit,
22575}
22576impl UAVIONIX_ADSB_OUT_CONTROL_DATA {
22577 pub const ENCODED_LEN: usize = 17usize;
22578 pub const DEFAULT: Self = Self {
22579 baroAltMSL: 0_i32,
22580 squawk: 0_u16,
22581 state: UavionixAdsbOutControlState::DEFAULT,
22582 emergencyStatus: UavionixAdsbEmergencyStatus::DEFAULT,
22583 flight_id: [0_u8; 8usize],
22584 x_bit: UavionixAdsbXbit::DEFAULT,
22585 };
22586 #[cfg(feature = "arbitrary")]
22587 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22588 use arbitrary::{Arbitrary, Unstructured};
22589 let mut buf = [0u8; 1024];
22590 rng.fill_bytes(&mut buf);
22591 let mut unstructured = Unstructured::new(&buf);
22592 Self::arbitrary(&mut unstructured).unwrap_or_default()
22593 }
22594}
22595impl Default for UAVIONIX_ADSB_OUT_CONTROL_DATA {
22596 fn default() -> Self {
22597 Self::DEFAULT.clone()
22598 }
22599}
22600impl MessageData for UAVIONIX_ADSB_OUT_CONTROL_DATA {
22601 type Message = MavMessage;
22602 const ID: u32 = 10007u32;
22603 const NAME: &'static str = "UAVIONIX_ADSB_OUT_CONTROL";
22604 const EXTRA_CRC: u8 = 71u8;
22605 const ENCODED_LEN: usize = 17usize;
22606 fn deser(
22607 _version: MavlinkVersion,
22608 __input: &[u8],
22609 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22610 let avail_len = __input.len();
22611 let mut payload_buf = [0; Self::ENCODED_LEN];
22612 let mut buf = if avail_len < Self::ENCODED_LEN {
22613 payload_buf[0..avail_len].copy_from_slice(__input);
22614 Bytes::new(&payload_buf)
22615 } else {
22616 Bytes::new(__input)
22617 };
22618 let mut __struct = Self::default();
22619 __struct.baroAltMSL = buf.get_i32_le();
22620 __struct.squawk = buf.get_u16_le();
22621 let tmp = buf.get_u8();
22622 __struct.state =
22623 UavionixAdsbOutControlState::from_bits(tmp & UavionixAdsbOutControlState::all().bits())
22624 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22625 flag_type: "UavionixAdsbOutControlState",
22626 value: tmp as u32,
22627 })?;
22628 let tmp = buf.get_u8();
22629 __struct.emergencyStatus =
22630 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22631 enum_type: "UavionixAdsbEmergencyStatus",
22632 value: tmp as u32,
22633 })?;
22634 for v in &mut __struct.flight_id {
22635 let val = buf.get_u8();
22636 *v = val;
22637 }
22638 let tmp = buf.get_u8();
22639 __struct.x_bit = UavionixAdsbXbit::from_bits(tmp & UavionixAdsbXbit::all().bits()).ok_or(
22640 ::mavlink_core::error::ParserError::InvalidFlag {
22641 flag_type: "UavionixAdsbXbit",
22642 value: tmp as u32,
22643 },
22644 )?;
22645 Ok(__struct)
22646 }
22647 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22648 let mut __tmp = BytesMut::new(bytes);
22649 #[allow(clippy::absurd_extreme_comparisons)]
22650 #[allow(unused_comparisons)]
22651 if __tmp.remaining() < Self::ENCODED_LEN {
22652 panic!(
22653 "buffer is too small (need {} bytes, but got {})",
22654 Self::ENCODED_LEN,
22655 __tmp.remaining(),
22656 )
22657 }
22658 __tmp.put_i32_le(self.baroAltMSL);
22659 __tmp.put_u16_le(self.squawk);
22660 __tmp.put_u8(self.state.bits());
22661 __tmp.put_u8(self.emergencyStatus as u8);
22662 for val in &self.flight_id {
22663 __tmp.put_u8(*val);
22664 }
22665 __tmp.put_u8(self.x_bit.bits());
22666 if matches!(version, MavlinkVersion::V2) {
22667 let len = __tmp.len();
22668 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22669 } else {
22670 __tmp.len()
22671 }
22672 }
22673}
22674#[doc = "id: 46"]
22675#[doc = "A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint."]
22676#[derive(Debug, Clone, PartialEq)]
22677#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22678#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22679pub struct MISSION_ITEM_REACHED_DATA {
22680 #[doc = "Sequence"]
22681 pub seq: u16,
22682}
22683impl MISSION_ITEM_REACHED_DATA {
22684 pub const ENCODED_LEN: usize = 2usize;
22685 pub const DEFAULT: Self = Self { seq: 0_u16 };
22686 #[cfg(feature = "arbitrary")]
22687 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22688 use arbitrary::{Arbitrary, Unstructured};
22689 let mut buf = [0u8; 1024];
22690 rng.fill_bytes(&mut buf);
22691 let mut unstructured = Unstructured::new(&buf);
22692 Self::arbitrary(&mut unstructured).unwrap_or_default()
22693 }
22694}
22695impl Default for MISSION_ITEM_REACHED_DATA {
22696 fn default() -> Self {
22697 Self::DEFAULT.clone()
22698 }
22699}
22700impl MessageData for MISSION_ITEM_REACHED_DATA {
22701 type Message = MavMessage;
22702 const ID: u32 = 46u32;
22703 const NAME: &'static str = "MISSION_ITEM_REACHED";
22704 const EXTRA_CRC: u8 = 11u8;
22705 const ENCODED_LEN: usize = 2usize;
22706 fn deser(
22707 _version: MavlinkVersion,
22708 __input: &[u8],
22709 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22710 let avail_len = __input.len();
22711 let mut payload_buf = [0; Self::ENCODED_LEN];
22712 let mut buf = if avail_len < Self::ENCODED_LEN {
22713 payload_buf[0..avail_len].copy_from_slice(__input);
22714 Bytes::new(&payload_buf)
22715 } else {
22716 Bytes::new(__input)
22717 };
22718 let mut __struct = Self::default();
22719 __struct.seq = buf.get_u16_le();
22720 Ok(__struct)
22721 }
22722 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22723 let mut __tmp = BytesMut::new(bytes);
22724 #[allow(clippy::absurd_extreme_comparisons)]
22725 #[allow(unused_comparisons)]
22726 if __tmp.remaining() < Self::ENCODED_LEN {
22727 panic!(
22728 "buffer is too small (need {} bytes, but got {})",
22729 Self::ENCODED_LEN,
22730 __tmp.remaining(),
22731 )
22732 }
22733 __tmp.put_u16_le(self.seq);
22734 if matches!(version, MavlinkVersion::V2) {
22735 let len = __tmp.len();
22736 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22737 } else {
22738 __tmp.len()
22739 }
22740 }
22741}
22742#[doc = "id: 86"]
22743#[doc = "Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system)."]
22744#[derive(Debug, Clone, PartialEq)]
22745#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22746#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22747pub struct SET_POSITION_TARGET_GLOBAL_INT_DATA {
22748 #[doc = "Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency."]
22749 pub time_boot_ms: u32,
22750 #[doc = "Latitude in WGS84 frame"]
22751 pub lat_int: i32,
22752 #[doc = "Longitude in WGS84 frame"]
22753 pub lon_int: i32,
22754 #[doc = "Altitude (MSL, Relative to home, or AGL - depending on frame)"]
22755 pub alt: f32,
22756 #[doc = "X velocity in NED frame"]
22757 pub vx: f32,
22758 #[doc = "Y velocity in NED frame"]
22759 pub vy: f32,
22760 #[doc = "Z velocity in NED frame"]
22761 pub vz: f32,
22762 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
22763 pub afx: f32,
22764 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
22765 pub afy: f32,
22766 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
22767 pub afz: f32,
22768 #[doc = "yaw setpoint"]
22769 pub yaw: f32,
22770 #[doc = "yaw rate setpoint"]
22771 pub yaw_rate: f32,
22772 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
22773 pub type_mask: PositionTargetTypemask,
22774 #[doc = "System ID"]
22775 pub target_system: u8,
22776 #[doc = "Component ID"]
22777 pub target_component: u8,
22778 #[doc = "Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)"]
22779 pub coordinate_frame: MavFrame,
22780}
22781impl SET_POSITION_TARGET_GLOBAL_INT_DATA {
22782 pub const ENCODED_LEN: usize = 53usize;
22783 pub const DEFAULT: Self = Self {
22784 time_boot_ms: 0_u32,
22785 lat_int: 0_i32,
22786 lon_int: 0_i32,
22787 alt: 0.0_f32,
22788 vx: 0.0_f32,
22789 vy: 0.0_f32,
22790 vz: 0.0_f32,
22791 afx: 0.0_f32,
22792 afy: 0.0_f32,
22793 afz: 0.0_f32,
22794 yaw: 0.0_f32,
22795 yaw_rate: 0.0_f32,
22796 type_mask: PositionTargetTypemask::DEFAULT,
22797 target_system: 0_u8,
22798 target_component: 0_u8,
22799 coordinate_frame: MavFrame::DEFAULT,
22800 };
22801 #[cfg(feature = "arbitrary")]
22802 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22803 use arbitrary::{Arbitrary, Unstructured};
22804 let mut buf = [0u8; 1024];
22805 rng.fill_bytes(&mut buf);
22806 let mut unstructured = Unstructured::new(&buf);
22807 Self::arbitrary(&mut unstructured).unwrap_or_default()
22808 }
22809}
22810impl Default for SET_POSITION_TARGET_GLOBAL_INT_DATA {
22811 fn default() -> Self {
22812 Self::DEFAULT.clone()
22813 }
22814}
22815impl MessageData for SET_POSITION_TARGET_GLOBAL_INT_DATA {
22816 type Message = MavMessage;
22817 const ID: u32 = 86u32;
22818 const NAME: &'static str = "SET_POSITION_TARGET_GLOBAL_INT";
22819 const EXTRA_CRC: u8 = 5u8;
22820 const ENCODED_LEN: usize = 53usize;
22821 fn deser(
22822 _version: MavlinkVersion,
22823 __input: &[u8],
22824 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22825 let avail_len = __input.len();
22826 let mut payload_buf = [0; Self::ENCODED_LEN];
22827 let mut buf = if avail_len < Self::ENCODED_LEN {
22828 payload_buf[0..avail_len].copy_from_slice(__input);
22829 Bytes::new(&payload_buf)
22830 } else {
22831 Bytes::new(__input)
22832 };
22833 let mut __struct = Self::default();
22834 __struct.time_boot_ms = buf.get_u32_le();
22835 __struct.lat_int = buf.get_i32_le();
22836 __struct.lon_int = buf.get_i32_le();
22837 __struct.alt = buf.get_f32_le();
22838 __struct.vx = buf.get_f32_le();
22839 __struct.vy = buf.get_f32_le();
22840 __struct.vz = buf.get_f32_le();
22841 __struct.afx = buf.get_f32_le();
22842 __struct.afy = buf.get_f32_le();
22843 __struct.afz = buf.get_f32_le();
22844 __struct.yaw = buf.get_f32_le();
22845 __struct.yaw_rate = buf.get_f32_le();
22846 let tmp = buf.get_u16_le();
22847 __struct.type_mask = PositionTargetTypemask::from_bits(
22848 tmp & PositionTargetTypemask::all().bits(),
22849 )
22850 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22851 flag_type: "PositionTargetTypemask",
22852 value: tmp as u32,
22853 })?;
22854 __struct.target_system = buf.get_u8();
22855 __struct.target_component = buf.get_u8();
22856 let tmp = buf.get_u8();
22857 __struct.coordinate_frame =
22858 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22859 enum_type: "MavFrame",
22860 value: tmp as u32,
22861 })?;
22862 Ok(__struct)
22863 }
22864 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22865 let mut __tmp = BytesMut::new(bytes);
22866 #[allow(clippy::absurd_extreme_comparisons)]
22867 #[allow(unused_comparisons)]
22868 if __tmp.remaining() < Self::ENCODED_LEN {
22869 panic!(
22870 "buffer is too small (need {} bytes, but got {})",
22871 Self::ENCODED_LEN,
22872 __tmp.remaining(),
22873 )
22874 }
22875 __tmp.put_u32_le(self.time_boot_ms);
22876 __tmp.put_i32_le(self.lat_int);
22877 __tmp.put_i32_le(self.lon_int);
22878 __tmp.put_f32_le(self.alt);
22879 __tmp.put_f32_le(self.vx);
22880 __tmp.put_f32_le(self.vy);
22881 __tmp.put_f32_le(self.vz);
22882 __tmp.put_f32_le(self.afx);
22883 __tmp.put_f32_le(self.afy);
22884 __tmp.put_f32_le(self.afz);
22885 __tmp.put_f32_le(self.yaw);
22886 __tmp.put_f32_le(self.yaw_rate);
22887 __tmp.put_u16_le(self.type_mask.bits());
22888 __tmp.put_u8(self.target_system);
22889 __tmp.put_u8(self.target_component);
22890 __tmp.put_u8(self.coordinate_frame as u8);
22891 if matches!(version, MavlinkVersion::V2) {
22892 let len = __tmp.len();
22893 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22894 } else {
22895 __tmp.len()
22896 }
22897 }
22898}
22899#[doc = "id: 413"]
22900#[doc = "Response to a REQUEST_EVENT in case of an error (e.g. the event is not available anymore)."]
22901#[derive(Debug, Clone, PartialEq)]
22902#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22903#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22904pub struct RESPONSE_EVENT_ERROR_DATA {
22905 #[doc = "Sequence number."]
22906 pub sequence: u16,
22907 #[doc = "Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT."]
22908 pub sequence_oldest_available: u16,
22909 #[doc = "System ID"]
22910 pub target_system: u8,
22911 #[doc = "Component ID"]
22912 pub target_component: u8,
22913 #[doc = "Error reason."]
22914 pub reason: MavEventErrorReason,
22915}
22916impl RESPONSE_EVENT_ERROR_DATA {
22917 pub const ENCODED_LEN: usize = 7usize;
22918 pub const DEFAULT: Self = Self {
22919 sequence: 0_u16,
22920 sequence_oldest_available: 0_u16,
22921 target_system: 0_u8,
22922 target_component: 0_u8,
22923 reason: MavEventErrorReason::DEFAULT,
22924 };
22925 #[cfg(feature = "arbitrary")]
22926 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22927 use arbitrary::{Arbitrary, Unstructured};
22928 let mut buf = [0u8; 1024];
22929 rng.fill_bytes(&mut buf);
22930 let mut unstructured = Unstructured::new(&buf);
22931 Self::arbitrary(&mut unstructured).unwrap_or_default()
22932 }
22933}
22934impl Default for RESPONSE_EVENT_ERROR_DATA {
22935 fn default() -> Self {
22936 Self::DEFAULT.clone()
22937 }
22938}
22939impl MessageData for RESPONSE_EVENT_ERROR_DATA {
22940 type Message = MavMessage;
22941 const ID: u32 = 413u32;
22942 const NAME: &'static str = "RESPONSE_EVENT_ERROR";
22943 const EXTRA_CRC: u8 = 77u8;
22944 const ENCODED_LEN: usize = 7usize;
22945 fn deser(
22946 _version: MavlinkVersion,
22947 __input: &[u8],
22948 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22949 let avail_len = __input.len();
22950 let mut payload_buf = [0; Self::ENCODED_LEN];
22951 let mut buf = if avail_len < Self::ENCODED_LEN {
22952 payload_buf[0..avail_len].copy_from_slice(__input);
22953 Bytes::new(&payload_buf)
22954 } else {
22955 Bytes::new(__input)
22956 };
22957 let mut __struct = Self::default();
22958 __struct.sequence = buf.get_u16_le();
22959 __struct.sequence_oldest_available = buf.get_u16_le();
22960 __struct.target_system = buf.get_u8();
22961 __struct.target_component = buf.get_u8();
22962 let tmp = buf.get_u8();
22963 __struct.reason =
22964 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22965 enum_type: "MavEventErrorReason",
22966 value: tmp as u32,
22967 })?;
22968 Ok(__struct)
22969 }
22970 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22971 let mut __tmp = BytesMut::new(bytes);
22972 #[allow(clippy::absurd_extreme_comparisons)]
22973 #[allow(unused_comparisons)]
22974 if __tmp.remaining() < Self::ENCODED_LEN {
22975 panic!(
22976 "buffer is too small (need {} bytes, but got {})",
22977 Self::ENCODED_LEN,
22978 __tmp.remaining(),
22979 )
22980 }
22981 __tmp.put_u16_le(self.sequence);
22982 __tmp.put_u16_le(self.sequence_oldest_available);
22983 __tmp.put_u8(self.target_system);
22984 __tmp.put_u8(self.target_component);
22985 __tmp.put_u8(self.reason as u8);
22986 if matches!(version, MavlinkVersion::V2) {
22987 let len = __tmp.len();
22988 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22989 } else {
22990 __tmp.len()
22991 }
22992 }
22993}
22994#[doc = "id: 411"]
22995#[doc = "Regular broadcast for the current latest event sequence number for a component. This is used to check for dropped events."]
22996#[derive(Debug, Clone, PartialEq)]
22997#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22998#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22999pub struct CURRENT_EVENT_SEQUENCE_DATA {
23000 #[doc = "Sequence number."]
23001 pub sequence: u16,
23002 #[doc = "Flag bitset."]
23003 pub flags: MavEventCurrentSequenceFlags,
23004}
23005impl CURRENT_EVENT_SEQUENCE_DATA {
23006 pub const ENCODED_LEN: usize = 3usize;
23007 pub const DEFAULT: Self = Self {
23008 sequence: 0_u16,
23009 flags: MavEventCurrentSequenceFlags::DEFAULT,
23010 };
23011 #[cfg(feature = "arbitrary")]
23012 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23013 use arbitrary::{Arbitrary, Unstructured};
23014 let mut buf = [0u8; 1024];
23015 rng.fill_bytes(&mut buf);
23016 let mut unstructured = Unstructured::new(&buf);
23017 Self::arbitrary(&mut unstructured).unwrap_or_default()
23018 }
23019}
23020impl Default for CURRENT_EVENT_SEQUENCE_DATA {
23021 fn default() -> Self {
23022 Self::DEFAULT.clone()
23023 }
23024}
23025impl MessageData for CURRENT_EVENT_SEQUENCE_DATA {
23026 type Message = MavMessage;
23027 const ID: u32 = 411u32;
23028 const NAME: &'static str = "CURRENT_EVENT_SEQUENCE";
23029 const EXTRA_CRC: u8 = 106u8;
23030 const ENCODED_LEN: usize = 3usize;
23031 fn deser(
23032 _version: MavlinkVersion,
23033 __input: &[u8],
23034 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23035 let avail_len = __input.len();
23036 let mut payload_buf = [0; Self::ENCODED_LEN];
23037 let mut buf = if avail_len < Self::ENCODED_LEN {
23038 payload_buf[0..avail_len].copy_from_slice(__input);
23039 Bytes::new(&payload_buf)
23040 } else {
23041 Bytes::new(__input)
23042 };
23043 let mut __struct = Self::default();
23044 __struct.sequence = buf.get_u16_le();
23045 let tmp = buf.get_u8();
23046 __struct.flags =
23047 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23048 enum_type: "MavEventCurrentSequenceFlags",
23049 value: tmp as u32,
23050 })?;
23051 Ok(__struct)
23052 }
23053 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23054 let mut __tmp = BytesMut::new(bytes);
23055 #[allow(clippy::absurd_extreme_comparisons)]
23056 #[allow(unused_comparisons)]
23057 if __tmp.remaining() < Self::ENCODED_LEN {
23058 panic!(
23059 "buffer is too small (need {} bytes, but got {})",
23060 Self::ENCODED_LEN,
23061 __tmp.remaining(),
23062 )
23063 }
23064 __tmp.put_u16_le(self.sequence);
23065 __tmp.put_u8(self.flags as u8);
23066 if matches!(version, MavlinkVersion::V2) {
23067 let len = __tmp.len();
23068 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23069 } else {
23070 __tmp.len()
23071 }
23072 }
23073}
23074#[doc = "id: 386"]
23075#[doc = "A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD."]
23076#[derive(Debug, Clone, PartialEq)]
23077#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23078#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23079pub struct CAN_FRAME_DATA {
23080 #[doc = "Frame ID"]
23081 pub id: u32,
23082 #[doc = "System ID."]
23083 pub target_system: u8,
23084 #[doc = "Component ID."]
23085 pub target_component: u8,
23086 #[doc = "Bus number"]
23087 pub bus: u8,
23088 #[doc = "Frame length"]
23089 pub len: u8,
23090 #[doc = "Frame data"]
23091 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23092 pub data: [u8; 8],
23093}
23094impl CAN_FRAME_DATA {
23095 pub const ENCODED_LEN: usize = 16usize;
23096 pub const DEFAULT: Self = Self {
23097 id: 0_u32,
23098 target_system: 0_u8,
23099 target_component: 0_u8,
23100 bus: 0_u8,
23101 len: 0_u8,
23102 data: [0_u8; 8usize],
23103 };
23104 #[cfg(feature = "arbitrary")]
23105 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23106 use arbitrary::{Arbitrary, Unstructured};
23107 let mut buf = [0u8; 1024];
23108 rng.fill_bytes(&mut buf);
23109 let mut unstructured = Unstructured::new(&buf);
23110 Self::arbitrary(&mut unstructured).unwrap_or_default()
23111 }
23112}
23113impl Default for CAN_FRAME_DATA {
23114 fn default() -> Self {
23115 Self::DEFAULT.clone()
23116 }
23117}
23118impl MessageData for CAN_FRAME_DATA {
23119 type Message = MavMessage;
23120 const ID: u32 = 386u32;
23121 const NAME: &'static str = "CAN_FRAME";
23122 const EXTRA_CRC: u8 = 132u8;
23123 const ENCODED_LEN: usize = 16usize;
23124 fn deser(
23125 _version: MavlinkVersion,
23126 __input: &[u8],
23127 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23128 let avail_len = __input.len();
23129 let mut payload_buf = [0; Self::ENCODED_LEN];
23130 let mut buf = if avail_len < Self::ENCODED_LEN {
23131 payload_buf[0..avail_len].copy_from_slice(__input);
23132 Bytes::new(&payload_buf)
23133 } else {
23134 Bytes::new(__input)
23135 };
23136 let mut __struct = Self::default();
23137 __struct.id = buf.get_u32_le();
23138 __struct.target_system = buf.get_u8();
23139 __struct.target_component = buf.get_u8();
23140 __struct.bus = buf.get_u8();
23141 __struct.len = buf.get_u8();
23142 for v in &mut __struct.data {
23143 let val = buf.get_u8();
23144 *v = val;
23145 }
23146 Ok(__struct)
23147 }
23148 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23149 let mut __tmp = BytesMut::new(bytes);
23150 #[allow(clippy::absurd_extreme_comparisons)]
23151 #[allow(unused_comparisons)]
23152 if __tmp.remaining() < Self::ENCODED_LEN {
23153 panic!(
23154 "buffer is too small (need {} bytes, but got {})",
23155 Self::ENCODED_LEN,
23156 __tmp.remaining(),
23157 )
23158 }
23159 __tmp.put_u32_le(self.id);
23160 __tmp.put_u8(self.target_system);
23161 __tmp.put_u8(self.target_component);
23162 __tmp.put_u8(self.bus);
23163 __tmp.put_u8(self.len);
23164 for val in &self.data {
23165 __tmp.put_u8(*val);
23166 }
23167 if matches!(version, MavlinkVersion::V2) {
23168 let len = __tmp.len();
23169 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23170 } else {
23171 __tmp.len()
23172 }
23173 }
23174}
23175#[doc = "id: 265"]
23176#[doc = "Orientation of a mount."]
23177#[derive(Debug, Clone, PartialEq)]
23178#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23179#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23180pub struct MOUNT_ORIENTATION_DATA {
23181 #[doc = "Timestamp (time since system boot)."]
23182 pub time_boot_ms: u32,
23183 #[doc = "Roll in global frame (set to NaN for invalid)."]
23184 pub roll: f32,
23185 #[doc = "Pitch in global frame (set to NaN for invalid)."]
23186 pub pitch: f32,
23187 #[doc = "Yaw relative to vehicle (set to NaN for invalid)."]
23188 pub yaw: f32,
23189 #[doc = "Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid)."]
23190 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23191 pub yaw_absolute: f32,
23192}
23193impl MOUNT_ORIENTATION_DATA {
23194 pub const ENCODED_LEN: usize = 20usize;
23195 pub const DEFAULT: Self = Self {
23196 time_boot_ms: 0_u32,
23197 roll: 0.0_f32,
23198 pitch: 0.0_f32,
23199 yaw: 0.0_f32,
23200 yaw_absolute: 0.0_f32,
23201 };
23202 #[cfg(feature = "arbitrary")]
23203 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23204 use arbitrary::{Arbitrary, Unstructured};
23205 let mut buf = [0u8; 1024];
23206 rng.fill_bytes(&mut buf);
23207 let mut unstructured = Unstructured::new(&buf);
23208 Self::arbitrary(&mut unstructured).unwrap_or_default()
23209 }
23210}
23211impl Default for MOUNT_ORIENTATION_DATA {
23212 fn default() -> Self {
23213 Self::DEFAULT.clone()
23214 }
23215}
23216impl MessageData for MOUNT_ORIENTATION_DATA {
23217 type Message = MavMessage;
23218 const ID: u32 = 265u32;
23219 const NAME: &'static str = "MOUNT_ORIENTATION";
23220 const EXTRA_CRC: u8 = 26u8;
23221 const ENCODED_LEN: usize = 20usize;
23222 fn deser(
23223 _version: MavlinkVersion,
23224 __input: &[u8],
23225 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23226 let avail_len = __input.len();
23227 let mut payload_buf = [0; Self::ENCODED_LEN];
23228 let mut buf = if avail_len < Self::ENCODED_LEN {
23229 payload_buf[0..avail_len].copy_from_slice(__input);
23230 Bytes::new(&payload_buf)
23231 } else {
23232 Bytes::new(__input)
23233 };
23234 let mut __struct = Self::default();
23235 __struct.time_boot_ms = buf.get_u32_le();
23236 __struct.roll = buf.get_f32_le();
23237 __struct.pitch = buf.get_f32_le();
23238 __struct.yaw = buf.get_f32_le();
23239 __struct.yaw_absolute = buf.get_f32_le();
23240 Ok(__struct)
23241 }
23242 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23243 let mut __tmp = BytesMut::new(bytes);
23244 #[allow(clippy::absurd_extreme_comparisons)]
23245 #[allow(unused_comparisons)]
23246 if __tmp.remaining() < Self::ENCODED_LEN {
23247 panic!(
23248 "buffer is too small (need {} bytes, but got {})",
23249 Self::ENCODED_LEN,
23250 __tmp.remaining(),
23251 )
23252 }
23253 __tmp.put_u32_le(self.time_boot_ms);
23254 __tmp.put_f32_le(self.roll);
23255 __tmp.put_f32_le(self.pitch);
23256 __tmp.put_f32_le(self.yaw);
23257 __tmp.put_f32_le(self.yaw_absolute);
23258 if matches!(version, MavlinkVersion::V2) {
23259 let len = __tmp.len();
23260 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23261 } else {
23262 __tmp.len()
23263 }
23264 }
23265}
23266#[doc = "id: 440"]
23267#[doc = "Illuminator status."]
23268#[derive(Debug, Clone, PartialEq)]
23269#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23270#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23271pub struct ILLUMINATOR_STATUS_DATA {
23272 #[doc = "Time since the start-up of the illuminator in ms"]
23273 pub uptime_ms: u32,
23274 #[doc = "Errors"]
23275 pub error_status: IlluminatorErrorFlags,
23276 #[doc = "Illuminator brightness"]
23277 pub brightness: f32,
23278 #[doc = "Illuminator strobing period in seconds"]
23279 pub strobe_period: f32,
23280 #[doc = "Illuminator strobing duty cycle"]
23281 pub strobe_duty_cycle: f32,
23282 #[doc = "Temperature in Celsius"]
23283 pub temp_c: f32,
23284 #[doc = "Minimum strobing period in seconds"]
23285 pub min_strobe_period: f32,
23286 #[doc = "Maximum strobing period in seconds"]
23287 pub max_strobe_period: f32,
23288 #[doc = "0: Illuminators OFF, 1: Illuminators ON"]
23289 pub enable: u8,
23290 #[doc = "Supported illuminator modes"]
23291 pub mode_bitmask: IlluminatorMode,
23292 #[doc = "Illuminator mode"]
23293 pub mode: IlluminatorMode,
23294}
23295impl ILLUMINATOR_STATUS_DATA {
23296 pub const ENCODED_LEN: usize = 35usize;
23297 pub const DEFAULT: Self = Self {
23298 uptime_ms: 0_u32,
23299 error_status: IlluminatorErrorFlags::DEFAULT,
23300 brightness: 0.0_f32,
23301 strobe_period: 0.0_f32,
23302 strobe_duty_cycle: 0.0_f32,
23303 temp_c: 0.0_f32,
23304 min_strobe_period: 0.0_f32,
23305 max_strobe_period: 0.0_f32,
23306 enable: 0_u8,
23307 mode_bitmask: IlluminatorMode::DEFAULT,
23308 mode: IlluminatorMode::DEFAULT,
23309 };
23310 #[cfg(feature = "arbitrary")]
23311 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23312 use arbitrary::{Arbitrary, Unstructured};
23313 let mut buf = [0u8; 1024];
23314 rng.fill_bytes(&mut buf);
23315 let mut unstructured = Unstructured::new(&buf);
23316 Self::arbitrary(&mut unstructured).unwrap_or_default()
23317 }
23318}
23319impl Default for ILLUMINATOR_STATUS_DATA {
23320 fn default() -> Self {
23321 Self::DEFAULT.clone()
23322 }
23323}
23324impl MessageData for ILLUMINATOR_STATUS_DATA {
23325 type Message = MavMessage;
23326 const ID: u32 = 440u32;
23327 const NAME: &'static str = "ILLUMINATOR_STATUS";
23328 const EXTRA_CRC: u8 = 66u8;
23329 const ENCODED_LEN: usize = 35usize;
23330 fn deser(
23331 _version: MavlinkVersion,
23332 __input: &[u8],
23333 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23334 let avail_len = __input.len();
23335 let mut payload_buf = [0; Self::ENCODED_LEN];
23336 let mut buf = if avail_len < Self::ENCODED_LEN {
23337 payload_buf[0..avail_len].copy_from_slice(__input);
23338 Bytes::new(&payload_buf)
23339 } else {
23340 Bytes::new(__input)
23341 };
23342 let mut __struct = Self::default();
23343 __struct.uptime_ms = buf.get_u32_le();
23344 let tmp = buf.get_u32_le();
23345 __struct.error_status = IlluminatorErrorFlags::from_bits(
23346 tmp & IlluminatorErrorFlags::all().bits(),
23347 )
23348 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
23349 flag_type: "IlluminatorErrorFlags",
23350 value: tmp as u32,
23351 })?;
23352 __struct.brightness = buf.get_f32_le();
23353 __struct.strobe_period = buf.get_f32_le();
23354 __struct.strobe_duty_cycle = buf.get_f32_le();
23355 __struct.temp_c = buf.get_f32_le();
23356 __struct.min_strobe_period = buf.get_f32_le();
23357 __struct.max_strobe_period = buf.get_f32_le();
23358 __struct.enable = buf.get_u8();
23359 let tmp = buf.get_u8();
23360 __struct.mode_bitmask =
23361 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23362 enum_type: "IlluminatorMode",
23363 value: tmp as u32,
23364 })?;
23365 let tmp = buf.get_u8();
23366 __struct.mode =
23367 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23368 enum_type: "IlluminatorMode",
23369 value: tmp as u32,
23370 })?;
23371 Ok(__struct)
23372 }
23373 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23374 let mut __tmp = BytesMut::new(bytes);
23375 #[allow(clippy::absurd_extreme_comparisons)]
23376 #[allow(unused_comparisons)]
23377 if __tmp.remaining() < Self::ENCODED_LEN {
23378 panic!(
23379 "buffer is too small (need {} bytes, but got {})",
23380 Self::ENCODED_LEN,
23381 __tmp.remaining(),
23382 )
23383 }
23384 __tmp.put_u32_le(self.uptime_ms);
23385 __tmp.put_u32_le(self.error_status.bits());
23386 __tmp.put_f32_le(self.brightness);
23387 __tmp.put_f32_le(self.strobe_period);
23388 __tmp.put_f32_le(self.strobe_duty_cycle);
23389 __tmp.put_f32_le(self.temp_c);
23390 __tmp.put_f32_le(self.min_strobe_period);
23391 __tmp.put_f32_le(self.max_strobe_period);
23392 __tmp.put_u8(self.enable);
23393 __tmp.put_u8(self.mode_bitmask as u8);
23394 __tmp.put_u8(self.mode as u8);
23395 if matches!(version, MavlinkVersion::V2) {
23396 let len = __tmp.len();
23397 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23398 } else {
23399 __tmp.len()
23400 }
23401 }
23402}
23403#[doc = "id: 6"]
23404#[doc = "Accept / deny control of this MAV."]
23405#[derive(Debug, Clone, PartialEq)]
23406#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23407#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23408pub struct CHANGE_OPERATOR_CONTROL_ACK_DATA {
23409 #[doc = "ID of the GCS this message"]
23410 pub gcs_system_id: u8,
23411 #[doc = "0: request control of this MAV, 1: Release control of this MAV"]
23412 pub control_request: u8,
23413 #[doc = "0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control"]
23414 pub ack: u8,
23415}
23416impl CHANGE_OPERATOR_CONTROL_ACK_DATA {
23417 pub const ENCODED_LEN: usize = 3usize;
23418 pub const DEFAULT: Self = Self {
23419 gcs_system_id: 0_u8,
23420 control_request: 0_u8,
23421 ack: 0_u8,
23422 };
23423 #[cfg(feature = "arbitrary")]
23424 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23425 use arbitrary::{Arbitrary, Unstructured};
23426 let mut buf = [0u8; 1024];
23427 rng.fill_bytes(&mut buf);
23428 let mut unstructured = Unstructured::new(&buf);
23429 Self::arbitrary(&mut unstructured).unwrap_or_default()
23430 }
23431}
23432impl Default for CHANGE_OPERATOR_CONTROL_ACK_DATA {
23433 fn default() -> Self {
23434 Self::DEFAULT.clone()
23435 }
23436}
23437impl MessageData for CHANGE_OPERATOR_CONTROL_ACK_DATA {
23438 type Message = MavMessage;
23439 const ID: u32 = 6u32;
23440 const NAME: &'static str = "CHANGE_OPERATOR_CONTROL_ACK";
23441 const EXTRA_CRC: u8 = 104u8;
23442 const ENCODED_LEN: usize = 3usize;
23443 fn deser(
23444 _version: MavlinkVersion,
23445 __input: &[u8],
23446 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23447 let avail_len = __input.len();
23448 let mut payload_buf = [0; Self::ENCODED_LEN];
23449 let mut buf = if avail_len < Self::ENCODED_LEN {
23450 payload_buf[0..avail_len].copy_from_slice(__input);
23451 Bytes::new(&payload_buf)
23452 } else {
23453 Bytes::new(__input)
23454 };
23455 let mut __struct = Self::default();
23456 __struct.gcs_system_id = buf.get_u8();
23457 __struct.control_request = buf.get_u8();
23458 __struct.ack = buf.get_u8();
23459 Ok(__struct)
23460 }
23461 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23462 let mut __tmp = BytesMut::new(bytes);
23463 #[allow(clippy::absurd_extreme_comparisons)]
23464 #[allow(unused_comparisons)]
23465 if __tmp.remaining() < Self::ENCODED_LEN {
23466 panic!(
23467 "buffer is too small (need {} bytes, but got {})",
23468 Self::ENCODED_LEN,
23469 __tmp.remaining(),
23470 )
23471 }
23472 __tmp.put_u8(self.gcs_system_id);
23473 __tmp.put_u8(self.control_request);
23474 __tmp.put_u8(self.ack);
23475 if matches!(version, MavlinkVersion::V2) {
23476 let len = __tmp.len();
23477 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23478 } else {
23479 __tmp.len()
23480 }
23481 }
23482}
23483#[doc = "id: 287"]
23484#[doc = "Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation."]
23485#[derive(Debug, Clone, PartialEq)]
23486#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23487#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23488pub struct GIMBAL_MANAGER_SET_PITCHYAW_DATA {
23489 #[doc = "High level gimbal manager flags to use."]
23490 pub flags: GimbalManagerFlags,
23491 #[doc = "Pitch angle (positive: up, negative: down, NaN to be ignored)."]
23492 pub pitch: f32,
23493 #[doc = "Yaw angle (positive: to the right, negative: to the left, NaN to be ignored)."]
23494 pub yaw: f32,
23495 #[doc = "Pitch angular rate (positive: up, negative: down, NaN to be ignored)."]
23496 pub pitch_rate: f32,
23497 #[doc = "Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored)."]
23498 pub yaw_rate: f32,
23499 #[doc = "System ID"]
23500 pub target_system: u8,
23501 #[doc = "Component ID"]
23502 pub target_component: u8,
23503 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
23504 pub gimbal_device_id: u8,
23505}
23506impl GIMBAL_MANAGER_SET_PITCHYAW_DATA {
23507 pub const ENCODED_LEN: usize = 23usize;
23508 pub const DEFAULT: Self = Self {
23509 flags: GimbalManagerFlags::DEFAULT,
23510 pitch: 0.0_f32,
23511 yaw: 0.0_f32,
23512 pitch_rate: 0.0_f32,
23513 yaw_rate: 0.0_f32,
23514 target_system: 0_u8,
23515 target_component: 0_u8,
23516 gimbal_device_id: 0_u8,
23517 };
23518 #[cfg(feature = "arbitrary")]
23519 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23520 use arbitrary::{Arbitrary, Unstructured};
23521 let mut buf = [0u8; 1024];
23522 rng.fill_bytes(&mut buf);
23523 let mut unstructured = Unstructured::new(&buf);
23524 Self::arbitrary(&mut unstructured).unwrap_or_default()
23525 }
23526}
23527impl Default for GIMBAL_MANAGER_SET_PITCHYAW_DATA {
23528 fn default() -> Self {
23529 Self::DEFAULT.clone()
23530 }
23531}
23532impl MessageData for GIMBAL_MANAGER_SET_PITCHYAW_DATA {
23533 type Message = MavMessage;
23534 const ID: u32 = 287u32;
23535 const NAME: &'static str = "GIMBAL_MANAGER_SET_PITCHYAW";
23536 const EXTRA_CRC: u8 = 1u8;
23537 const ENCODED_LEN: usize = 23usize;
23538 fn deser(
23539 _version: MavlinkVersion,
23540 __input: &[u8],
23541 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23542 let avail_len = __input.len();
23543 let mut payload_buf = [0; Self::ENCODED_LEN];
23544 let mut buf = if avail_len < Self::ENCODED_LEN {
23545 payload_buf[0..avail_len].copy_from_slice(__input);
23546 Bytes::new(&payload_buf)
23547 } else {
23548 Bytes::new(__input)
23549 };
23550 let mut __struct = Self::default();
23551 let tmp = buf.get_u32_le();
23552 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
23553 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
23554 flag_type: "GimbalManagerFlags",
23555 value: tmp as u32,
23556 })?;
23557 __struct.pitch = buf.get_f32_le();
23558 __struct.yaw = buf.get_f32_le();
23559 __struct.pitch_rate = buf.get_f32_le();
23560 __struct.yaw_rate = buf.get_f32_le();
23561 __struct.target_system = buf.get_u8();
23562 __struct.target_component = buf.get_u8();
23563 __struct.gimbal_device_id = buf.get_u8();
23564 Ok(__struct)
23565 }
23566 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23567 let mut __tmp = BytesMut::new(bytes);
23568 #[allow(clippy::absurd_extreme_comparisons)]
23569 #[allow(unused_comparisons)]
23570 if __tmp.remaining() < Self::ENCODED_LEN {
23571 panic!(
23572 "buffer is too small (need {} bytes, but got {})",
23573 Self::ENCODED_LEN,
23574 __tmp.remaining(),
23575 )
23576 }
23577 __tmp.put_u32_le(self.flags.bits());
23578 __tmp.put_f32_le(self.pitch);
23579 __tmp.put_f32_le(self.yaw);
23580 __tmp.put_f32_le(self.pitch_rate);
23581 __tmp.put_f32_le(self.yaw_rate);
23582 __tmp.put_u8(self.target_system);
23583 __tmp.put_u8(self.target_component);
23584 __tmp.put_u8(self.gimbal_device_id);
23585 if matches!(version, MavlinkVersion::V2) {
23586 let len = __tmp.len();
23587 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23588 } else {
23589 __tmp.len()
23590 }
23591 }
23592}
23593#[doc = "id: 12918"]
23594#[doc = "Transmitter (remote ID system) is enabled and ready to start sending location and other required information. This is streamed by transmitter. A flight controller uses it as a condition to arm."]
23595#[derive(Debug, Clone, PartialEq)]
23596#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23597#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23598pub struct OPEN_DRONE_ID_ARM_STATUS_DATA {
23599 #[doc = "Status level indicating if arming is allowed."]
23600 pub status: MavOdidArmStatus,
23601 #[doc = "Text error message, should be empty if status is good to arm. Fill with nulls in unused portion."]
23602 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23603 pub error: [u8; 50],
23604}
23605impl OPEN_DRONE_ID_ARM_STATUS_DATA {
23606 pub const ENCODED_LEN: usize = 51usize;
23607 pub const DEFAULT: Self = Self {
23608 status: MavOdidArmStatus::DEFAULT,
23609 error: [0_u8; 50usize],
23610 };
23611 #[cfg(feature = "arbitrary")]
23612 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23613 use arbitrary::{Arbitrary, Unstructured};
23614 let mut buf = [0u8; 1024];
23615 rng.fill_bytes(&mut buf);
23616 let mut unstructured = Unstructured::new(&buf);
23617 Self::arbitrary(&mut unstructured).unwrap_or_default()
23618 }
23619}
23620impl Default for OPEN_DRONE_ID_ARM_STATUS_DATA {
23621 fn default() -> Self {
23622 Self::DEFAULT.clone()
23623 }
23624}
23625impl MessageData for OPEN_DRONE_ID_ARM_STATUS_DATA {
23626 type Message = MavMessage;
23627 const ID: u32 = 12918u32;
23628 const NAME: &'static str = "OPEN_DRONE_ID_ARM_STATUS";
23629 const EXTRA_CRC: u8 = 139u8;
23630 const ENCODED_LEN: usize = 51usize;
23631 fn deser(
23632 _version: MavlinkVersion,
23633 __input: &[u8],
23634 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23635 let avail_len = __input.len();
23636 let mut payload_buf = [0; Self::ENCODED_LEN];
23637 let mut buf = if avail_len < Self::ENCODED_LEN {
23638 payload_buf[0..avail_len].copy_from_slice(__input);
23639 Bytes::new(&payload_buf)
23640 } else {
23641 Bytes::new(__input)
23642 };
23643 let mut __struct = Self::default();
23644 let tmp = buf.get_u8();
23645 __struct.status =
23646 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23647 enum_type: "MavOdidArmStatus",
23648 value: tmp as u32,
23649 })?;
23650 for v in &mut __struct.error {
23651 let val = buf.get_u8();
23652 *v = val;
23653 }
23654 Ok(__struct)
23655 }
23656 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23657 let mut __tmp = BytesMut::new(bytes);
23658 #[allow(clippy::absurd_extreme_comparisons)]
23659 #[allow(unused_comparisons)]
23660 if __tmp.remaining() < Self::ENCODED_LEN {
23661 panic!(
23662 "buffer is too small (need {} bytes, but got {})",
23663 Self::ENCODED_LEN,
23664 __tmp.remaining(),
23665 )
23666 }
23667 __tmp.put_u8(self.status as u8);
23668 for val in &self.error {
23669 __tmp.put_u8(*val);
23670 }
23671 if matches!(version, MavlinkVersion::V2) {
23672 let len = __tmp.len();
23673 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23674 } else {
23675 __tmp.len()
23676 }
23677 }
23678}
23679#[doc = "id: 340"]
23680#[doc = "The global position resulting from GPS and sensor fusion."]
23681#[derive(Debug, Clone, PartialEq)]
23682#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23683#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23684pub struct UTM_GLOBAL_POSITION_DATA {
23685 #[doc = "Time of applicability of position (microseconds since UNIX epoch)."]
23686 pub time: u64,
23687 #[doc = "Latitude (WGS84)"]
23688 pub lat: i32,
23689 #[doc = "Longitude (WGS84)"]
23690 pub lon: i32,
23691 #[doc = "Altitude (WGS84)"]
23692 pub alt: i32,
23693 #[doc = "Altitude above ground"]
23694 pub relative_alt: i32,
23695 #[doc = "Next waypoint, latitude (WGS84)"]
23696 pub next_lat: i32,
23697 #[doc = "Next waypoint, longitude (WGS84)"]
23698 pub next_lon: i32,
23699 #[doc = "Next waypoint, altitude (WGS84)"]
23700 pub next_alt: i32,
23701 #[doc = "Ground X speed (latitude, positive north)"]
23702 pub vx: i16,
23703 #[doc = "Ground Y speed (longitude, positive east)"]
23704 pub vy: i16,
23705 #[doc = "Ground Z speed (altitude, positive down)"]
23706 pub vz: i16,
23707 #[doc = "Horizontal position uncertainty (standard deviation)"]
23708 pub h_acc: u16,
23709 #[doc = "Altitude uncertainty (standard deviation)"]
23710 pub v_acc: u16,
23711 #[doc = "Speed uncertainty (standard deviation)"]
23712 pub vel_acc: u16,
23713 #[doc = "Time until next update. Set to 0 if unknown or in data driven mode."]
23714 pub update_rate: u16,
23715 #[doc = "Unique UAS ID."]
23716 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23717 pub uas_id: [u8; 18],
23718 #[doc = "Flight state"]
23719 pub flight_state: UtmFlightState,
23720 #[doc = "Bitwise OR combination of the data available flags."]
23721 pub flags: UtmDataAvailFlags,
23722}
23723impl UTM_GLOBAL_POSITION_DATA {
23724 pub const ENCODED_LEN: usize = 70usize;
23725 pub const DEFAULT: Self = Self {
23726 time: 0_u64,
23727 lat: 0_i32,
23728 lon: 0_i32,
23729 alt: 0_i32,
23730 relative_alt: 0_i32,
23731 next_lat: 0_i32,
23732 next_lon: 0_i32,
23733 next_alt: 0_i32,
23734 vx: 0_i16,
23735 vy: 0_i16,
23736 vz: 0_i16,
23737 h_acc: 0_u16,
23738 v_acc: 0_u16,
23739 vel_acc: 0_u16,
23740 update_rate: 0_u16,
23741 uas_id: [0_u8; 18usize],
23742 flight_state: UtmFlightState::DEFAULT,
23743 flags: UtmDataAvailFlags::DEFAULT,
23744 };
23745 #[cfg(feature = "arbitrary")]
23746 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23747 use arbitrary::{Arbitrary, Unstructured};
23748 let mut buf = [0u8; 1024];
23749 rng.fill_bytes(&mut buf);
23750 let mut unstructured = Unstructured::new(&buf);
23751 Self::arbitrary(&mut unstructured).unwrap_or_default()
23752 }
23753}
23754impl Default for UTM_GLOBAL_POSITION_DATA {
23755 fn default() -> Self {
23756 Self::DEFAULT.clone()
23757 }
23758}
23759impl MessageData for UTM_GLOBAL_POSITION_DATA {
23760 type Message = MavMessage;
23761 const ID: u32 = 340u32;
23762 const NAME: &'static str = "UTM_GLOBAL_POSITION";
23763 const EXTRA_CRC: u8 = 99u8;
23764 const ENCODED_LEN: usize = 70usize;
23765 fn deser(
23766 _version: MavlinkVersion,
23767 __input: &[u8],
23768 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23769 let avail_len = __input.len();
23770 let mut payload_buf = [0; Self::ENCODED_LEN];
23771 let mut buf = if avail_len < Self::ENCODED_LEN {
23772 payload_buf[0..avail_len].copy_from_slice(__input);
23773 Bytes::new(&payload_buf)
23774 } else {
23775 Bytes::new(__input)
23776 };
23777 let mut __struct = Self::default();
23778 __struct.time = buf.get_u64_le();
23779 __struct.lat = buf.get_i32_le();
23780 __struct.lon = buf.get_i32_le();
23781 __struct.alt = buf.get_i32_le();
23782 __struct.relative_alt = buf.get_i32_le();
23783 __struct.next_lat = buf.get_i32_le();
23784 __struct.next_lon = buf.get_i32_le();
23785 __struct.next_alt = buf.get_i32_le();
23786 __struct.vx = buf.get_i16_le();
23787 __struct.vy = buf.get_i16_le();
23788 __struct.vz = buf.get_i16_le();
23789 __struct.h_acc = buf.get_u16_le();
23790 __struct.v_acc = buf.get_u16_le();
23791 __struct.vel_acc = buf.get_u16_le();
23792 __struct.update_rate = buf.get_u16_le();
23793 for v in &mut __struct.uas_id {
23794 let val = buf.get_u8();
23795 *v = val;
23796 }
23797 let tmp = buf.get_u8();
23798 __struct.flight_state =
23799 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23800 enum_type: "UtmFlightState",
23801 value: tmp as u32,
23802 })?;
23803 let tmp = buf.get_u8();
23804 __struct.flags = UtmDataAvailFlags::from_bits(tmp & UtmDataAvailFlags::all().bits())
23805 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
23806 flag_type: "UtmDataAvailFlags",
23807 value: tmp as u32,
23808 })?;
23809 Ok(__struct)
23810 }
23811 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23812 let mut __tmp = BytesMut::new(bytes);
23813 #[allow(clippy::absurd_extreme_comparisons)]
23814 #[allow(unused_comparisons)]
23815 if __tmp.remaining() < Self::ENCODED_LEN {
23816 panic!(
23817 "buffer is too small (need {} bytes, but got {})",
23818 Self::ENCODED_LEN,
23819 __tmp.remaining(),
23820 )
23821 }
23822 __tmp.put_u64_le(self.time);
23823 __tmp.put_i32_le(self.lat);
23824 __tmp.put_i32_le(self.lon);
23825 __tmp.put_i32_le(self.alt);
23826 __tmp.put_i32_le(self.relative_alt);
23827 __tmp.put_i32_le(self.next_lat);
23828 __tmp.put_i32_le(self.next_lon);
23829 __tmp.put_i32_le(self.next_alt);
23830 __tmp.put_i16_le(self.vx);
23831 __tmp.put_i16_le(self.vy);
23832 __tmp.put_i16_le(self.vz);
23833 __tmp.put_u16_le(self.h_acc);
23834 __tmp.put_u16_le(self.v_acc);
23835 __tmp.put_u16_le(self.vel_acc);
23836 __tmp.put_u16_le(self.update_rate);
23837 for val in &self.uas_id {
23838 __tmp.put_u8(*val);
23839 }
23840 __tmp.put_u8(self.flight_state as u8);
23841 __tmp.put_u8(self.flags.bits());
23842 if matches!(version, MavlinkVersion::V2) {
23843 let len = __tmp.len();
23844 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23845 } else {
23846 __tmp.len()
23847 }
23848 }
23849}
23850#[doc = "id: 70"]
23851#[doc = "The RAW values of the RC channels sent to the MAV to override info received from the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. Note carefully the semantic differences between the first 8 channels and the subsequent channels."]
23852#[derive(Debug, Clone, PartialEq)]
23853#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23854#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23855pub struct RC_CHANNELS_OVERRIDE_DATA {
23856 #[doc = "RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
23857 pub chan1_raw: u16,
23858 #[doc = "RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
23859 pub chan2_raw: u16,
23860 #[doc = "RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
23861 pub chan3_raw: u16,
23862 #[doc = "RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
23863 pub chan4_raw: u16,
23864 #[doc = "RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
23865 pub chan5_raw: u16,
23866 #[doc = "RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
23867 pub chan6_raw: u16,
23868 #[doc = "RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
23869 pub chan7_raw: u16,
23870 #[doc = "RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
23871 pub chan8_raw: u16,
23872 #[doc = "System ID"]
23873 pub target_system: u8,
23874 #[doc = "Component ID"]
23875 pub target_component: u8,
23876 #[doc = "RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
23877 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23878 pub chan9_raw: u16,
23879 #[doc = "RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
23880 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23881 pub chan10_raw: u16,
23882 #[doc = "RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
23883 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23884 pub chan11_raw: u16,
23885 #[doc = "RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
23886 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23887 pub chan12_raw: u16,
23888 #[doc = "RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
23889 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23890 pub chan13_raw: u16,
23891 #[doc = "RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
23892 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23893 pub chan14_raw: u16,
23894 #[doc = "RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
23895 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23896 pub chan15_raw: u16,
23897 #[doc = "RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
23898 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23899 pub chan16_raw: u16,
23900 #[doc = "RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
23901 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23902 pub chan17_raw: u16,
23903 #[doc = "RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
23904 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23905 pub chan18_raw: u16,
23906}
23907impl RC_CHANNELS_OVERRIDE_DATA {
23908 pub const ENCODED_LEN: usize = 38usize;
23909 pub const DEFAULT: Self = Self {
23910 chan1_raw: 0_u16,
23911 chan2_raw: 0_u16,
23912 chan3_raw: 0_u16,
23913 chan4_raw: 0_u16,
23914 chan5_raw: 0_u16,
23915 chan6_raw: 0_u16,
23916 chan7_raw: 0_u16,
23917 chan8_raw: 0_u16,
23918 target_system: 0_u8,
23919 target_component: 0_u8,
23920 chan9_raw: 0_u16,
23921 chan10_raw: 0_u16,
23922 chan11_raw: 0_u16,
23923 chan12_raw: 0_u16,
23924 chan13_raw: 0_u16,
23925 chan14_raw: 0_u16,
23926 chan15_raw: 0_u16,
23927 chan16_raw: 0_u16,
23928 chan17_raw: 0_u16,
23929 chan18_raw: 0_u16,
23930 };
23931 #[cfg(feature = "arbitrary")]
23932 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23933 use arbitrary::{Arbitrary, Unstructured};
23934 let mut buf = [0u8; 1024];
23935 rng.fill_bytes(&mut buf);
23936 let mut unstructured = Unstructured::new(&buf);
23937 Self::arbitrary(&mut unstructured).unwrap_or_default()
23938 }
23939}
23940impl Default for RC_CHANNELS_OVERRIDE_DATA {
23941 fn default() -> Self {
23942 Self::DEFAULT.clone()
23943 }
23944}
23945impl MessageData for RC_CHANNELS_OVERRIDE_DATA {
23946 type Message = MavMessage;
23947 const ID: u32 = 70u32;
23948 const NAME: &'static str = "RC_CHANNELS_OVERRIDE";
23949 const EXTRA_CRC: u8 = 124u8;
23950 const ENCODED_LEN: usize = 38usize;
23951 fn deser(
23952 _version: MavlinkVersion,
23953 __input: &[u8],
23954 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23955 let avail_len = __input.len();
23956 let mut payload_buf = [0; Self::ENCODED_LEN];
23957 let mut buf = if avail_len < Self::ENCODED_LEN {
23958 payload_buf[0..avail_len].copy_from_slice(__input);
23959 Bytes::new(&payload_buf)
23960 } else {
23961 Bytes::new(__input)
23962 };
23963 let mut __struct = Self::default();
23964 __struct.chan1_raw = buf.get_u16_le();
23965 __struct.chan2_raw = buf.get_u16_le();
23966 __struct.chan3_raw = buf.get_u16_le();
23967 __struct.chan4_raw = buf.get_u16_le();
23968 __struct.chan5_raw = buf.get_u16_le();
23969 __struct.chan6_raw = buf.get_u16_le();
23970 __struct.chan7_raw = buf.get_u16_le();
23971 __struct.chan8_raw = buf.get_u16_le();
23972 __struct.target_system = buf.get_u8();
23973 __struct.target_component = buf.get_u8();
23974 __struct.chan9_raw = buf.get_u16_le();
23975 __struct.chan10_raw = buf.get_u16_le();
23976 __struct.chan11_raw = buf.get_u16_le();
23977 __struct.chan12_raw = buf.get_u16_le();
23978 __struct.chan13_raw = buf.get_u16_le();
23979 __struct.chan14_raw = buf.get_u16_le();
23980 __struct.chan15_raw = buf.get_u16_le();
23981 __struct.chan16_raw = buf.get_u16_le();
23982 __struct.chan17_raw = buf.get_u16_le();
23983 __struct.chan18_raw = buf.get_u16_le();
23984 Ok(__struct)
23985 }
23986 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23987 let mut __tmp = BytesMut::new(bytes);
23988 #[allow(clippy::absurd_extreme_comparisons)]
23989 #[allow(unused_comparisons)]
23990 if __tmp.remaining() < Self::ENCODED_LEN {
23991 panic!(
23992 "buffer is too small (need {} bytes, but got {})",
23993 Self::ENCODED_LEN,
23994 __tmp.remaining(),
23995 )
23996 }
23997 __tmp.put_u16_le(self.chan1_raw);
23998 __tmp.put_u16_le(self.chan2_raw);
23999 __tmp.put_u16_le(self.chan3_raw);
24000 __tmp.put_u16_le(self.chan4_raw);
24001 __tmp.put_u16_le(self.chan5_raw);
24002 __tmp.put_u16_le(self.chan6_raw);
24003 __tmp.put_u16_le(self.chan7_raw);
24004 __tmp.put_u16_le(self.chan8_raw);
24005 __tmp.put_u8(self.target_system);
24006 __tmp.put_u8(self.target_component);
24007 __tmp.put_u16_le(self.chan9_raw);
24008 __tmp.put_u16_le(self.chan10_raw);
24009 __tmp.put_u16_le(self.chan11_raw);
24010 __tmp.put_u16_le(self.chan12_raw);
24011 __tmp.put_u16_le(self.chan13_raw);
24012 __tmp.put_u16_le(self.chan14_raw);
24013 __tmp.put_u16_le(self.chan15_raw);
24014 __tmp.put_u16_le(self.chan16_raw);
24015 __tmp.put_u16_le(self.chan17_raw);
24016 __tmp.put_u16_le(self.chan18_raw);
24017 if matches!(version, MavlinkVersion::V2) {
24018 let len = __tmp.len();
24019 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24020 } else {
24021 __tmp.len()
24022 }
24023 }
24024}
24025#[doc = "id: 26"]
24026#[doc = "The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units."]
24027#[derive(Debug, Clone, PartialEq)]
24028#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24029#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24030pub struct SCALED_IMU_DATA {
24031 #[doc = "Timestamp (time since system boot)."]
24032 pub time_boot_ms: u32,
24033 #[doc = "X acceleration"]
24034 pub xacc: i16,
24035 #[doc = "Y acceleration"]
24036 pub yacc: i16,
24037 #[doc = "Z acceleration"]
24038 pub zacc: i16,
24039 #[doc = "Angular speed around X axis"]
24040 pub xgyro: i16,
24041 #[doc = "Angular speed around Y axis"]
24042 pub ygyro: i16,
24043 #[doc = "Angular speed around Z axis"]
24044 pub zgyro: i16,
24045 #[doc = "X Magnetic field"]
24046 pub xmag: i16,
24047 #[doc = "Y Magnetic field"]
24048 pub ymag: i16,
24049 #[doc = "Z Magnetic field"]
24050 pub zmag: i16,
24051 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
24052 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24053 pub temperature: i16,
24054}
24055impl SCALED_IMU_DATA {
24056 pub const ENCODED_LEN: usize = 24usize;
24057 pub const DEFAULT: Self = Self {
24058 time_boot_ms: 0_u32,
24059 xacc: 0_i16,
24060 yacc: 0_i16,
24061 zacc: 0_i16,
24062 xgyro: 0_i16,
24063 ygyro: 0_i16,
24064 zgyro: 0_i16,
24065 xmag: 0_i16,
24066 ymag: 0_i16,
24067 zmag: 0_i16,
24068 temperature: 0_i16,
24069 };
24070 #[cfg(feature = "arbitrary")]
24071 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24072 use arbitrary::{Arbitrary, Unstructured};
24073 let mut buf = [0u8; 1024];
24074 rng.fill_bytes(&mut buf);
24075 let mut unstructured = Unstructured::new(&buf);
24076 Self::arbitrary(&mut unstructured).unwrap_or_default()
24077 }
24078}
24079impl Default for SCALED_IMU_DATA {
24080 fn default() -> Self {
24081 Self::DEFAULT.clone()
24082 }
24083}
24084impl MessageData for SCALED_IMU_DATA {
24085 type Message = MavMessage;
24086 const ID: u32 = 26u32;
24087 const NAME: &'static str = "SCALED_IMU";
24088 const EXTRA_CRC: u8 = 170u8;
24089 const ENCODED_LEN: usize = 24usize;
24090 fn deser(
24091 _version: MavlinkVersion,
24092 __input: &[u8],
24093 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24094 let avail_len = __input.len();
24095 let mut payload_buf = [0; Self::ENCODED_LEN];
24096 let mut buf = if avail_len < Self::ENCODED_LEN {
24097 payload_buf[0..avail_len].copy_from_slice(__input);
24098 Bytes::new(&payload_buf)
24099 } else {
24100 Bytes::new(__input)
24101 };
24102 let mut __struct = Self::default();
24103 __struct.time_boot_ms = buf.get_u32_le();
24104 __struct.xacc = buf.get_i16_le();
24105 __struct.yacc = buf.get_i16_le();
24106 __struct.zacc = buf.get_i16_le();
24107 __struct.xgyro = buf.get_i16_le();
24108 __struct.ygyro = buf.get_i16_le();
24109 __struct.zgyro = buf.get_i16_le();
24110 __struct.xmag = buf.get_i16_le();
24111 __struct.ymag = buf.get_i16_le();
24112 __struct.zmag = buf.get_i16_le();
24113 __struct.temperature = buf.get_i16_le();
24114 Ok(__struct)
24115 }
24116 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24117 let mut __tmp = BytesMut::new(bytes);
24118 #[allow(clippy::absurd_extreme_comparisons)]
24119 #[allow(unused_comparisons)]
24120 if __tmp.remaining() < Self::ENCODED_LEN {
24121 panic!(
24122 "buffer is too small (need {} bytes, but got {})",
24123 Self::ENCODED_LEN,
24124 __tmp.remaining(),
24125 )
24126 }
24127 __tmp.put_u32_le(self.time_boot_ms);
24128 __tmp.put_i16_le(self.xacc);
24129 __tmp.put_i16_le(self.yacc);
24130 __tmp.put_i16_le(self.zacc);
24131 __tmp.put_i16_le(self.xgyro);
24132 __tmp.put_i16_le(self.ygyro);
24133 __tmp.put_i16_le(self.zgyro);
24134 __tmp.put_i16_le(self.xmag);
24135 __tmp.put_i16_le(self.ymag);
24136 __tmp.put_i16_le(self.zmag);
24137 __tmp.put_i16_le(self.temperature);
24138 if matches!(version, MavlinkVersion::V2) {
24139 let len = __tmp.len();
24140 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24141 } else {
24142 __tmp.len()
24143 }
24144 }
24145}
24146#[doc = "id: 67"]
24147#[doc = "Data stream status information."]
24148#[derive(Debug, Clone, PartialEq)]
24149#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24150#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24151pub struct DATA_STREAM_DATA {
24152 #[doc = "The message rate"]
24153 pub message_rate: u16,
24154 #[doc = "The ID of the requested data stream"]
24155 pub stream_id: u8,
24156 #[doc = "1 stream is enabled, 0 stream is stopped."]
24157 pub on_off: u8,
24158}
24159impl DATA_STREAM_DATA {
24160 pub const ENCODED_LEN: usize = 4usize;
24161 pub const DEFAULT: Self = Self {
24162 message_rate: 0_u16,
24163 stream_id: 0_u8,
24164 on_off: 0_u8,
24165 };
24166 #[cfg(feature = "arbitrary")]
24167 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24168 use arbitrary::{Arbitrary, Unstructured};
24169 let mut buf = [0u8; 1024];
24170 rng.fill_bytes(&mut buf);
24171 let mut unstructured = Unstructured::new(&buf);
24172 Self::arbitrary(&mut unstructured).unwrap_or_default()
24173 }
24174}
24175impl Default for DATA_STREAM_DATA {
24176 fn default() -> Self {
24177 Self::DEFAULT.clone()
24178 }
24179}
24180impl MessageData for DATA_STREAM_DATA {
24181 type Message = MavMessage;
24182 const ID: u32 = 67u32;
24183 const NAME: &'static str = "DATA_STREAM";
24184 const EXTRA_CRC: u8 = 21u8;
24185 const ENCODED_LEN: usize = 4usize;
24186 fn deser(
24187 _version: MavlinkVersion,
24188 __input: &[u8],
24189 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24190 let avail_len = __input.len();
24191 let mut payload_buf = [0; Self::ENCODED_LEN];
24192 let mut buf = if avail_len < Self::ENCODED_LEN {
24193 payload_buf[0..avail_len].copy_from_slice(__input);
24194 Bytes::new(&payload_buf)
24195 } else {
24196 Bytes::new(__input)
24197 };
24198 let mut __struct = Self::default();
24199 __struct.message_rate = buf.get_u16_le();
24200 __struct.stream_id = buf.get_u8();
24201 __struct.on_off = buf.get_u8();
24202 Ok(__struct)
24203 }
24204 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24205 let mut __tmp = BytesMut::new(bytes);
24206 #[allow(clippy::absurd_extreme_comparisons)]
24207 #[allow(unused_comparisons)]
24208 if __tmp.remaining() < Self::ENCODED_LEN {
24209 panic!(
24210 "buffer is too small (need {} bytes, but got {})",
24211 Self::ENCODED_LEN,
24212 __tmp.remaining(),
24213 )
24214 }
24215 __tmp.put_u16_le(self.message_rate);
24216 __tmp.put_u8(self.stream_id);
24217 __tmp.put_u8(self.on_off);
24218 if matches!(version, MavlinkVersion::V2) {
24219 let len = __tmp.len();
24220 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24221 } else {
24222 __tmp.len()
24223 }
24224 }
24225}
24226#[doc = "id: 118"]
24227#[doc = "Reply to LOG_REQUEST_LIST."]
24228#[derive(Debug, Clone, PartialEq)]
24229#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24230#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24231pub struct LOG_ENTRY_DATA {
24232 #[doc = "UTC timestamp of log since 1970, or 0 if not available"]
24233 pub time_utc: u32,
24234 #[doc = "Size of the log (may be approximate)"]
24235 pub size: u32,
24236 #[doc = "Log id"]
24237 pub id: u16,
24238 #[doc = "Total number of logs"]
24239 pub num_logs: u16,
24240 #[doc = "High log number"]
24241 pub last_log_num: u16,
24242}
24243impl LOG_ENTRY_DATA {
24244 pub const ENCODED_LEN: usize = 14usize;
24245 pub const DEFAULT: Self = Self {
24246 time_utc: 0_u32,
24247 size: 0_u32,
24248 id: 0_u16,
24249 num_logs: 0_u16,
24250 last_log_num: 0_u16,
24251 };
24252 #[cfg(feature = "arbitrary")]
24253 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24254 use arbitrary::{Arbitrary, Unstructured};
24255 let mut buf = [0u8; 1024];
24256 rng.fill_bytes(&mut buf);
24257 let mut unstructured = Unstructured::new(&buf);
24258 Self::arbitrary(&mut unstructured).unwrap_or_default()
24259 }
24260}
24261impl Default for LOG_ENTRY_DATA {
24262 fn default() -> Self {
24263 Self::DEFAULT.clone()
24264 }
24265}
24266impl MessageData for LOG_ENTRY_DATA {
24267 type Message = MavMessage;
24268 const ID: u32 = 118u32;
24269 const NAME: &'static str = "LOG_ENTRY";
24270 const EXTRA_CRC: u8 = 56u8;
24271 const ENCODED_LEN: usize = 14usize;
24272 fn deser(
24273 _version: MavlinkVersion,
24274 __input: &[u8],
24275 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24276 let avail_len = __input.len();
24277 let mut payload_buf = [0; Self::ENCODED_LEN];
24278 let mut buf = if avail_len < Self::ENCODED_LEN {
24279 payload_buf[0..avail_len].copy_from_slice(__input);
24280 Bytes::new(&payload_buf)
24281 } else {
24282 Bytes::new(__input)
24283 };
24284 let mut __struct = Self::default();
24285 __struct.time_utc = buf.get_u32_le();
24286 __struct.size = buf.get_u32_le();
24287 __struct.id = buf.get_u16_le();
24288 __struct.num_logs = buf.get_u16_le();
24289 __struct.last_log_num = buf.get_u16_le();
24290 Ok(__struct)
24291 }
24292 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24293 let mut __tmp = BytesMut::new(bytes);
24294 #[allow(clippy::absurd_extreme_comparisons)]
24295 #[allow(unused_comparisons)]
24296 if __tmp.remaining() < Self::ENCODED_LEN {
24297 panic!(
24298 "buffer is too small (need {} bytes, but got {})",
24299 Self::ENCODED_LEN,
24300 __tmp.remaining(),
24301 )
24302 }
24303 __tmp.put_u32_le(self.time_utc);
24304 __tmp.put_u32_le(self.size);
24305 __tmp.put_u16_le(self.id);
24306 __tmp.put_u16_le(self.num_logs);
24307 __tmp.put_u16_le(self.last_log_num);
24308 if matches!(version, MavlinkVersion::V2) {
24309 let len = __tmp.len();
24310 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24311 } else {
24312 __tmp.len()
24313 }
24314 }
24315}
24316#[doc = "id: 4"]
24317#[doc = "A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at <https://mavlink.io/en/services/ping.html>."]
24318#[derive(Debug, Clone, PartialEq)]
24319#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24320#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24321pub struct PING_DATA {
24322 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
24323 pub time_usec: u64,
24324 #[doc = "PING sequence"]
24325 pub seq: u32,
24326 #[doc = "0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system"]
24327 pub target_system: u8,
24328 #[doc = "0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component."]
24329 pub target_component: u8,
24330}
24331impl PING_DATA {
24332 pub const ENCODED_LEN: usize = 14usize;
24333 pub const DEFAULT: Self = Self {
24334 time_usec: 0_u64,
24335 seq: 0_u32,
24336 target_system: 0_u8,
24337 target_component: 0_u8,
24338 };
24339 #[cfg(feature = "arbitrary")]
24340 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24341 use arbitrary::{Arbitrary, Unstructured};
24342 let mut buf = [0u8; 1024];
24343 rng.fill_bytes(&mut buf);
24344 let mut unstructured = Unstructured::new(&buf);
24345 Self::arbitrary(&mut unstructured).unwrap_or_default()
24346 }
24347}
24348impl Default for PING_DATA {
24349 fn default() -> Self {
24350 Self::DEFAULT.clone()
24351 }
24352}
24353impl MessageData for PING_DATA {
24354 type Message = MavMessage;
24355 const ID: u32 = 4u32;
24356 const NAME: &'static str = "PING";
24357 const EXTRA_CRC: u8 = 237u8;
24358 const ENCODED_LEN: usize = 14usize;
24359 fn deser(
24360 _version: MavlinkVersion,
24361 __input: &[u8],
24362 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24363 let avail_len = __input.len();
24364 let mut payload_buf = [0; Self::ENCODED_LEN];
24365 let mut buf = if avail_len < Self::ENCODED_LEN {
24366 payload_buf[0..avail_len].copy_from_slice(__input);
24367 Bytes::new(&payload_buf)
24368 } else {
24369 Bytes::new(__input)
24370 };
24371 let mut __struct = Self::default();
24372 __struct.time_usec = buf.get_u64_le();
24373 __struct.seq = buf.get_u32_le();
24374 __struct.target_system = buf.get_u8();
24375 __struct.target_component = buf.get_u8();
24376 Ok(__struct)
24377 }
24378 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24379 let mut __tmp = BytesMut::new(bytes);
24380 #[allow(clippy::absurd_extreme_comparisons)]
24381 #[allow(unused_comparisons)]
24382 if __tmp.remaining() < Self::ENCODED_LEN {
24383 panic!(
24384 "buffer is too small (need {} bytes, but got {})",
24385 Self::ENCODED_LEN,
24386 __tmp.remaining(),
24387 )
24388 }
24389 __tmp.put_u64_le(self.time_usec);
24390 __tmp.put_u32_le(self.seq);
24391 __tmp.put_u8(self.target_system);
24392 __tmp.put_u8(self.target_component);
24393 if matches!(version, MavlinkVersion::V2) {
24394 let len = __tmp.len();
24395 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24396 } else {
24397 __tmp.len()
24398 }
24399 }
24400}
24401#[doc = "id: 85"]
24402#[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way."]
24403#[derive(Debug, Clone, PartialEq)]
24404#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24405#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24406pub struct POSITION_TARGET_LOCAL_NED_DATA {
24407 #[doc = "Timestamp (time since system boot)."]
24408 pub time_boot_ms: u32,
24409 #[doc = "X Position in NED frame"]
24410 pub x: f32,
24411 #[doc = "Y Position in NED frame"]
24412 pub y: f32,
24413 #[doc = "Z Position in NED frame (note, altitude is negative in NED)"]
24414 pub z: f32,
24415 #[doc = "X velocity in NED frame"]
24416 pub vx: f32,
24417 #[doc = "Y velocity in NED frame"]
24418 pub vy: f32,
24419 #[doc = "Z velocity in NED frame"]
24420 pub vz: f32,
24421 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
24422 pub afx: f32,
24423 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
24424 pub afy: f32,
24425 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
24426 pub afz: f32,
24427 #[doc = "yaw setpoint"]
24428 pub yaw: f32,
24429 #[doc = "yaw rate setpoint"]
24430 pub yaw_rate: f32,
24431 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
24432 pub type_mask: PositionTargetTypemask,
24433 #[doc = "Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9"]
24434 pub coordinate_frame: MavFrame,
24435}
24436impl POSITION_TARGET_LOCAL_NED_DATA {
24437 pub const ENCODED_LEN: usize = 51usize;
24438 pub const DEFAULT: Self = Self {
24439 time_boot_ms: 0_u32,
24440 x: 0.0_f32,
24441 y: 0.0_f32,
24442 z: 0.0_f32,
24443 vx: 0.0_f32,
24444 vy: 0.0_f32,
24445 vz: 0.0_f32,
24446 afx: 0.0_f32,
24447 afy: 0.0_f32,
24448 afz: 0.0_f32,
24449 yaw: 0.0_f32,
24450 yaw_rate: 0.0_f32,
24451 type_mask: PositionTargetTypemask::DEFAULT,
24452 coordinate_frame: MavFrame::DEFAULT,
24453 };
24454 #[cfg(feature = "arbitrary")]
24455 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24456 use arbitrary::{Arbitrary, Unstructured};
24457 let mut buf = [0u8; 1024];
24458 rng.fill_bytes(&mut buf);
24459 let mut unstructured = Unstructured::new(&buf);
24460 Self::arbitrary(&mut unstructured).unwrap_or_default()
24461 }
24462}
24463impl Default for POSITION_TARGET_LOCAL_NED_DATA {
24464 fn default() -> Self {
24465 Self::DEFAULT.clone()
24466 }
24467}
24468impl MessageData for POSITION_TARGET_LOCAL_NED_DATA {
24469 type Message = MavMessage;
24470 const ID: u32 = 85u32;
24471 const NAME: &'static str = "POSITION_TARGET_LOCAL_NED";
24472 const EXTRA_CRC: u8 = 140u8;
24473 const ENCODED_LEN: usize = 51usize;
24474 fn deser(
24475 _version: MavlinkVersion,
24476 __input: &[u8],
24477 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24478 let avail_len = __input.len();
24479 let mut payload_buf = [0; Self::ENCODED_LEN];
24480 let mut buf = if avail_len < Self::ENCODED_LEN {
24481 payload_buf[0..avail_len].copy_from_slice(__input);
24482 Bytes::new(&payload_buf)
24483 } else {
24484 Bytes::new(__input)
24485 };
24486 let mut __struct = Self::default();
24487 __struct.time_boot_ms = buf.get_u32_le();
24488 __struct.x = buf.get_f32_le();
24489 __struct.y = buf.get_f32_le();
24490 __struct.z = buf.get_f32_le();
24491 __struct.vx = buf.get_f32_le();
24492 __struct.vy = buf.get_f32_le();
24493 __struct.vz = buf.get_f32_le();
24494 __struct.afx = buf.get_f32_le();
24495 __struct.afy = buf.get_f32_le();
24496 __struct.afz = buf.get_f32_le();
24497 __struct.yaw = buf.get_f32_le();
24498 __struct.yaw_rate = buf.get_f32_le();
24499 let tmp = buf.get_u16_le();
24500 __struct.type_mask = PositionTargetTypemask::from_bits(
24501 tmp & PositionTargetTypemask::all().bits(),
24502 )
24503 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
24504 flag_type: "PositionTargetTypemask",
24505 value: tmp as u32,
24506 })?;
24507 let tmp = buf.get_u8();
24508 __struct.coordinate_frame =
24509 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24510 enum_type: "MavFrame",
24511 value: tmp as u32,
24512 })?;
24513 Ok(__struct)
24514 }
24515 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24516 let mut __tmp = BytesMut::new(bytes);
24517 #[allow(clippy::absurd_extreme_comparisons)]
24518 #[allow(unused_comparisons)]
24519 if __tmp.remaining() < Self::ENCODED_LEN {
24520 panic!(
24521 "buffer is too small (need {} bytes, but got {})",
24522 Self::ENCODED_LEN,
24523 __tmp.remaining(),
24524 )
24525 }
24526 __tmp.put_u32_le(self.time_boot_ms);
24527 __tmp.put_f32_le(self.x);
24528 __tmp.put_f32_le(self.y);
24529 __tmp.put_f32_le(self.z);
24530 __tmp.put_f32_le(self.vx);
24531 __tmp.put_f32_le(self.vy);
24532 __tmp.put_f32_le(self.vz);
24533 __tmp.put_f32_le(self.afx);
24534 __tmp.put_f32_le(self.afy);
24535 __tmp.put_f32_le(self.afz);
24536 __tmp.put_f32_le(self.yaw);
24537 __tmp.put_f32_le(self.yaw_rate);
24538 __tmp.put_u16_le(self.type_mask.bits());
24539 __tmp.put_u8(self.coordinate_frame as u8);
24540 if matches!(version, MavlinkVersion::V2) {
24541 let len = __tmp.len();
24542 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24543 } else {
24544 __tmp.len()
24545 }
24546 }
24547}
24548#[doc = "id: 116"]
24549#[doc = "The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units."]
24550#[derive(Debug, Clone, PartialEq)]
24551#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24552#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24553pub struct SCALED_IMU2_DATA {
24554 #[doc = "Timestamp (time since system boot)."]
24555 pub time_boot_ms: u32,
24556 #[doc = "X acceleration"]
24557 pub xacc: i16,
24558 #[doc = "Y acceleration"]
24559 pub yacc: i16,
24560 #[doc = "Z acceleration"]
24561 pub zacc: i16,
24562 #[doc = "Angular speed around X axis"]
24563 pub xgyro: i16,
24564 #[doc = "Angular speed around Y axis"]
24565 pub ygyro: i16,
24566 #[doc = "Angular speed around Z axis"]
24567 pub zgyro: i16,
24568 #[doc = "X Magnetic field"]
24569 pub xmag: i16,
24570 #[doc = "Y Magnetic field"]
24571 pub ymag: i16,
24572 #[doc = "Z Magnetic field"]
24573 pub zmag: i16,
24574 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
24575 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24576 pub temperature: i16,
24577}
24578impl SCALED_IMU2_DATA {
24579 pub const ENCODED_LEN: usize = 24usize;
24580 pub const DEFAULT: Self = Self {
24581 time_boot_ms: 0_u32,
24582 xacc: 0_i16,
24583 yacc: 0_i16,
24584 zacc: 0_i16,
24585 xgyro: 0_i16,
24586 ygyro: 0_i16,
24587 zgyro: 0_i16,
24588 xmag: 0_i16,
24589 ymag: 0_i16,
24590 zmag: 0_i16,
24591 temperature: 0_i16,
24592 };
24593 #[cfg(feature = "arbitrary")]
24594 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24595 use arbitrary::{Arbitrary, Unstructured};
24596 let mut buf = [0u8; 1024];
24597 rng.fill_bytes(&mut buf);
24598 let mut unstructured = Unstructured::new(&buf);
24599 Self::arbitrary(&mut unstructured).unwrap_or_default()
24600 }
24601}
24602impl Default for SCALED_IMU2_DATA {
24603 fn default() -> Self {
24604 Self::DEFAULT.clone()
24605 }
24606}
24607impl MessageData for SCALED_IMU2_DATA {
24608 type Message = MavMessage;
24609 const ID: u32 = 116u32;
24610 const NAME: &'static str = "SCALED_IMU2";
24611 const EXTRA_CRC: u8 = 76u8;
24612 const ENCODED_LEN: usize = 24usize;
24613 fn deser(
24614 _version: MavlinkVersion,
24615 __input: &[u8],
24616 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24617 let avail_len = __input.len();
24618 let mut payload_buf = [0; Self::ENCODED_LEN];
24619 let mut buf = if avail_len < Self::ENCODED_LEN {
24620 payload_buf[0..avail_len].copy_from_slice(__input);
24621 Bytes::new(&payload_buf)
24622 } else {
24623 Bytes::new(__input)
24624 };
24625 let mut __struct = Self::default();
24626 __struct.time_boot_ms = buf.get_u32_le();
24627 __struct.xacc = buf.get_i16_le();
24628 __struct.yacc = buf.get_i16_le();
24629 __struct.zacc = buf.get_i16_le();
24630 __struct.xgyro = buf.get_i16_le();
24631 __struct.ygyro = buf.get_i16_le();
24632 __struct.zgyro = buf.get_i16_le();
24633 __struct.xmag = buf.get_i16_le();
24634 __struct.ymag = buf.get_i16_le();
24635 __struct.zmag = buf.get_i16_le();
24636 __struct.temperature = buf.get_i16_le();
24637 Ok(__struct)
24638 }
24639 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24640 let mut __tmp = BytesMut::new(bytes);
24641 #[allow(clippy::absurd_extreme_comparisons)]
24642 #[allow(unused_comparisons)]
24643 if __tmp.remaining() < Self::ENCODED_LEN {
24644 panic!(
24645 "buffer is too small (need {} bytes, but got {})",
24646 Self::ENCODED_LEN,
24647 __tmp.remaining(),
24648 )
24649 }
24650 __tmp.put_u32_le(self.time_boot_ms);
24651 __tmp.put_i16_le(self.xacc);
24652 __tmp.put_i16_le(self.yacc);
24653 __tmp.put_i16_le(self.zacc);
24654 __tmp.put_i16_le(self.xgyro);
24655 __tmp.put_i16_le(self.ygyro);
24656 __tmp.put_i16_le(self.zgyro);
24657 __tmp.put_i16_le(self.xmag);
24658 __tmp.put_i16_le(self.ymag);
24659 __tmp.put_i16_le(self.zmag);
24660 __tmp.put_i16_le(self.temperature);
24661 if matches!(version, MavlinkVersion::V2) {
24662 let len = __tmp.len();
24663 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24664 } else {
24665 __tmp.len()
24666 }
24667 }
24668}
24669#[doc = "id: 233"]
24670#[doc = "RTCM message for injecting into the onboard GPS (used for DGPS)."]
24671#[derive(Debug, Clone, PartialEq)]
24672#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24673#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24674pub struct GPS_RTCM_DATA_DATA {
24675 #[doc = "LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order."]
24676 pub flags: u8,
24677 #[doc = "data length"]
24678 pub len: u8,
24679 #[doc = "RTCM message (may be fragmented)"]
24680 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24681 pub data: [u8; 180],
24682}
24683impl GPS_RTCM_DATA_DATA {
24684 pub const ENCODED_LEN: usize = 182usize;
24685 pub const DEFAULT: Self = Self {
24686 flags: 0_u8,
24687 len: 0_u8,
24688 data: [0_u8; 180usize],
24689 };
24690 #[cfg(feature = "arbitrary")]
24691 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24692 use arbitrary::{Arbitrary, Unstructured};
24693 let mut buf = [0u8; 1024];
24694 rng.fill_bytes(&mut buf);
24695 let mut unstructured = Unstructured::new(&buf);
24696 Self::arbitrary(&mut unstructured).unwrap_or_default()
24697 }
24698}
24699impl Default for GPS_RTCM_DATA_DATA {
24700 fn default() -> Self {
24701 Self::DEFAULT.clone()
24702 }
24703}
24704impl MessageData for GPS_RTCM_DATA_DATA {
24705 type Message = MavMessage;
24706 const ID: u32 = 233u32;
24707 const NAME: &'static str = "GPS_RTCM_DATA";
24708 const EXTRA_CRC: u8 = 35u8;
24709 const ENCODED_LEN: usize = 182usize;
24710 fn deser(
24711 _version: MavlinkVersion,
24712 __input: &[u8],
24713 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24714 let avail_len = __input.len();
24715 let mut payload_buf = [0; Self::ENCODED_LEN];
24716 let mut buf = if avail_len < Self::ENCODED_LEN {
24717 payload_buf[0..avail_len].copy_from_slice(__input);
24718 Bytes::new(&payload_buf)
24719 } else {
24720 Bytes::new(__input)
24721 };
24722 let mut __struct = Self::default();
24723 __struct.flags = buf.get_u8();
24724 __struct.len = buf.get_u8();
24725 for v in &mut __struct.data {
24726 let val = buf.get_u8();
24727 *v = val;
24728 }
24729 Ok(__struct)
24730 }
24731 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24732 let mut __tmp = BytesMut::new(bytes);
24733 #[allow(clippy::absurd_extreme_comparisons)]
24734 #[allow(unused_comparisons)]
24735 if __tmp.remaining() < Self::ENCODED_LEN {
24736 panic!(
24737 "buffer is too small (need {} bytes, but got {})",
24738 Self::ENCODED_LEN,
24739 __tmp.remaining(),
24740 )
24741 }
24742 __tmp.put_u8(self.flags);
24743 __tmp.put_u8(self.len);
24744 for val in &self.data {
24745 __tmp.put_u8(*val);
24746 }
24747 if matches!(version, MavlinkVersion::V2) {
24748 let len = __tmp.len();
24749 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24750 } else {
24751 __tmp.len()
24752 }
24753 }
24754}
24755#[doc = "id: 11"]
24756#[doc = "Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component."]
24757#[derive(Debug, Clone, PartialEq)]
24758#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24759#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24760pub struct SET_MODE_DATA {
24761 #[doc = "The new autopilot-specific mode. This field can be ignored by an autopilot."]
24762 pub custom_mode: u32,
24763 #[doc = "The system setting the mode"]
24764 pub target_system: u8,
24765 #[doc = "The new base mode."]
24766 pub base_mode: MavMode,
24767}
24768impl SET_MODE_DATA {
24769 pub const ENCODED_LEN: usize = 6usize;
24770 pub const DEFAULT: Self = Self {
24771 custom_mode: 0_u32,
24772 target_system: 0_u8,
24773 base_mode: MavMode::DEFAULT,
24774 };
24775 #[cfg(feature = "arbitrary")]
24776 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24777 use arbitrary::{Arbitrary, Unstructured};
24778 let mut buf = [0u8; 1024];
24779 rng.fill_bytes(&mut buf);
24780 let mut unstructured = Unstructured::new(&buf);
24781 Self::arbitrary(&mut unstructured).unwrap_or_default()
24782 }
24783}
24784impl Default for SET_MODE_DATA {
24785 fn default() -> Self {
24786 Self::DEFAULT.clone()
24787 }
24788}
24789impl MessageData for SET_MODE_DATA {
24790 type Message = MavMessage;
24791 const ID: u32 = 11u32;
24792 const NAME: &'static str = "SET_MODE";
24793 const EXTRA_CRC: u8 = 89u8;
24794 const ENCODED_LEN: usize = 6usize;
24795 fn deser(
24796 _version: MavlinkVersion,
24797 __input: &[u8],
24798 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24799 let avail_len = __input.len();
24800 let mut payload_buf = [0; Self::ENCODED_LEN];
24801 let mut buf = if avail_len < Self::ENCODED_LEN {
24802 payload_buf[0..avail_len].copy_from_slice(__input);
24803 Bytes::new(&payload_buf)
24804 } else {
24805 Bytes::new(__input)
24806 };
24807 let mut __struct = Self::default();
24808 __struct.custom_mode = buf.get_u32_le();
24809 __struct.target_system = buf.get_u8();
24810 let tmp = buf.get_u8();
24811 __struct.base_mode =
24812 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24813 enum_type: "MavMode",
24814 value: tmp as u32,
24815 })?;
24816 Ok(__struct)
24817 }
24818 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24819 let mut __tmp = BytesMut::new(bytes);
24820 #[allow(clippy::absurd_extreme_comparisons)]
24821 #[allow(unused_comparisons)]
24822 if __tmp.remaining() < Self::ENCODED_LEN {
24823 panic!(
24824 "buffer is too small (need {} bytes, but got {})",
24825 Self::ENCODED_LEN,
24826 __tmp.remaining(),
24827 )
24828 }
24829 __tmp.put_u32_le(self.custom_mode);
24830 __tmp.put_u8(self.target_system);
24831 __tmp.put_u8(self.base_mode as u8);
24832 if matches!(version, MavlinkVersion::V2) {
24833 let len = __tmp.len();
24834 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24835 } else {
24836 __tmp.len()
24837 }
24838 }
24839}
24840#[doc = "id: 230"]
24841#[doc = "Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovation test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovation test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user."]
24842#[derive(Debug, Clone, PartialEq)]
24843#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24844#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24845pub struct ESTIMATOR_STATUS_DATA {
24846 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
24847 pub time_usec: u64,
24848 #[doc = "Velocity innovation test ratio"]
24849 pub vel_ratio: f32,
24850 #[doc = "Horizontal position innovation test ratio"]
24851 pub pos_horiz_ratio: f32,
24852 #[doc = "Vertical position innovation test ratio"]
24853 pub pos_vert_ratio: f32,
24854 #[doc = "Magnetometer innovation test ratio"]
24855 pub mag_ratio: f32,
24856 #[doc = "Height above terrain innovation test ratio"]
24857 pub hagl_ratio: f32,
24858 #[doc = "True airspeed innovation test ratio"]
24859 pub tas_ratio: f32,
24860 #[doc = "Horizontal position 1-STD accuracy relative to the EKF local origin"]
24861 pub pos_horiz_accuracy: f32,
24862 #[doc = "Vertical position 1-STD accuracy relative to the EKF local origin"]
24863 pub pos_vert_accuracy: f32,
24864 #[doc = "Bitmap indicating which EKF outputs are valid."]
24865 pub flags: EstimatorStatusFlags,
24866}
24867impl ESTIMATOR_STATUS_DATA {
24868 pub const ENCODED_LEN: usize = 42usize;
24869 pub const DEFAULT: Self = Self {
24870 time_usec: 0_u64,
24871 vel_ratio: 0.0_f32,
24872 pos_horiz_ratio: 0.0_f32,
24873 pos_vert_ratio: 0.0_f32,
24874 mag_ratio: 0.0_f32,
24875 hagl_ratio: 0.0_f32,
24876 tas_ratio: 0.0_f32,
24877 pos_horiz_accuracy: 0.0_f32,
24878 pos_vert_accuracy: 0.0_f32,
24879 flags: EstimatorStatusFlags::DEFAULT,
24880 };
24881 #[cfg(feature = "arbitrary")]
24882 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24883 use arbitrary::{Arbitrary, Unstructured};
24884 let mut buf = [0u8; 1024];
24885 rng.fill_bytes(&mut buf);
24886 let mut unstructured = Unstructured::new(&buf);
24887 Self::arbitrary(&mut unstructured).unwrap_or_default()
24888 }
24889}
24890impl Default for ESTIMATOR_STATUS_DATA {
24891 fn default() -> Self {
24892 Self::DEFAULT.clone()
24893 }
24894}
24895impl MessageData for ESTIMATOR_STATUS_DATA {
24896 type Message = MavMessage;
24897 const ID: u32 = 230u32;
24898 const NAME: &'static str = "ESTIMATOR_STATUS";
24899 const EXTRA_CRC: u8 = 163u8;
24900 const ENCODED_LEN: usize = 42usize;
24901 fn deser(
24902 _version: MavlinkVersion,
24903 __input: &[u8],
24904 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24905 let avail_len = __input.len();
24906 let mut payload_buf = [0; Self::ENCODED_LEN];
24907 let mut buf = if avail_len < Self::ENCODED_LEN {
24908 payload_buf[0..avail_len].copy_from_slice(__input);
24909 Bytes::new(&payload_buf)
24910 } else {
24911 Bytes::new(__input)
24912 };
24913 let mut __struct = Self::default();
24914 __struct.time_usec = buf.get_u64_le();
24915 __struct.vel_ratio = buf.get_f32_le();
24916 __struct.pos_horiz_ratio = buf.get_f32_le();
24917 __struct.pos_vert_ratio = buf.get_f32_le();
24918 __struct.mag_ratio = buf.get_f32_le();
24919 __struct.hagl_ratio = buf.get_f32_le();
24920 __struct.tas_ratio = buf.get_f32_le();
24921 __struct.pos_horiz_accuracy = buf.get_f32_le();
24922 __struct.pos_vert_accuracy = buf.get_f32_le();
24923 let tmp = buf.get_u16_le();
24924 __struct.flags = EstimatorStatusFlags::from_bits(tmp & EstimatorStatusFlags::all().bits())
24925 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
24926 flag_type: "EstimatorStatusFlags",
24927 value: tmp as u32,
24928 })?;
24929 Ok(__struct)
24930 }
24931 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24932 let mut __tmp = BytesMut::new(bytes);
24933 #[allow(clippy::absurd_extreme_comparisons)]
24934 #[allow(unused_comparisons)]
24935 if __tmp.remaining() < Self::ENCODED_LEN {
24936 panic!(
24937 "buffer is too small (need {} bytes, but got {})",
24938 Self::ENCODED_LEN,
24939 __tmp.remaining(),
24940 )
24941 }
24942 __tmp.put_u64_le(self.time_usec);
24943 __tmp.put_f32_le(self.vel_ratio);
24944 __tmp.put_f32_le(self.pos_horiz_ratio);
24945 __tmp.put_f32_le(self.pos_vert_ratio);
24946 __tmp.put_f32_le(self.mag_ratio);
24947 __tmp.put_f32_le(self.hagl_ratio);
24948 __tmp.put_f32_le(self.tas_ratio);
24949 __tmp.put_f32_le(self.pos_horiz_accuracy);
24950 __tmp.put_f32_le(self.pos_vert_accuracy);
24951 __tmp.put_u16_le(self.flags.bits());
24952 if matches!(version, MavlinkVersion::V2) {
24953 let len = __tmp.len();
24954 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24955 } else {
24956 __tmp.len()
24957 }
24958 }
24959}
24960#[doc = "id: 90"]
24961#[doc = "Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations."]
24962#[derive(Debug, Clone, PartialEq)]
24963#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24964#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24965pub struct HIL_STATE_DATA {
24966 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
24967 pub time_usec: u64,
24968 #[doc = "Roll angle"]
24969 pub roll: f32,
24970 #[doc = "Pitch angle"]
24971 pub pitch: f32,
24972 #[doc = "Yaw angle"]
24973 pub yaw: f32,
24974 #[doc = "Body frame roll / phi angular speed"]
24975 pub rollspeed: f32,
24976 #[doc = "Body frame pitch / theta angular speed"]
24977 pub pitchspeed: f32,
24978 #[doc = "Body frame yaw / psi angular speed"]
24979 pub yawspeed: f32,
24980 #[doc = "Latitude"]
24981 pub lat: i32,
24982 #[doc = "Longitude"]
24983 pub lon: i32,
24984 #[doc = "Altitude"]
24985 pub alt: i32,
24986 #[doc = "Ground X Speed (Latitude)"]
24987 pub vx: i16,
24988 #[doc = "Ground Y Speed (Longitude)"]
24989 pub vy: i16,
24990 #[doc = "Ground Z Speed (Altitude)"]
24991 pub vz: i16,
24992 #[doc = "X acceleration"]
24993 pub xacc: i16,
24994 #[doc = "Y acceleration"]
24995 pub yacc: i16,
24996 #[doc = "Z acceleration"]
24997 pub zacc: i16,
24998}
24999impl HIL_STATE_DATA {
25000 pub const ENCODED_LEN: usize = 56usize;
25001 pub const DEFAULT: Self = Self {
25002 time_usec: 0_u64,
25003 roll: 0.0_f32,
25004 pitch: 0.0_f32,
25005 yaw: 0.0_f32,
25006 rollspeed: 0.0_f32,
25007 pitchspeed: 0.0_f32,
25008 yawspeed: 0.0_f32,
25009 lat: 0_i32,
25010 lon: 0_i32,
25011 alt: 0_i32,
25012 vx: 0_i16,
25013 vy: 0_i16,
25014 vz: 0_i16,
25015 xacc: 0_i16,
25016 yacc: 0_i16,
25017 zacc: 0_i16,
25018 };
25019 #[cfg(feature = "arbitrary")]
25020 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25021 use arbitrary::{Arbitrary, Unstructured};
25022 let mut buf = [0u8; 1024];
25023 rng.fill_bytes(&mut buf);
25024 let mut unstructured = Unstructured::new(&buf);
25025 Self::arbitrary(&mut unstructured).unwrap_or_default()
25026 }
25027}
25028impl Default for HIL_STATE_DATA {
25029 fn default() -> Self {
25030 Self::DEFAULT.clone()
25031 }
25032}
25033impl MessageData for HIL_STATE_DATA {
25034 type Message = MavMessage;
25035 const ID: u32 = 90u32;
25036 const NAME: &'static str = "HIL_STATE";
25037 const EXTRA_CRC: u8 = 183u8;
25038 const ENCODED_LEN: usize = 56usize;
25039 fn deser(
25040 _version: MavlinkVersion,
25041 __input: &[u8],
25042 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25043 let avail_len = __input.len();
25044 let mut payload_buf = [0; Self::ENCODED_LEN];
25045 let mut buf = if avail_len < Self::ENCODED_LEN {
25046 payload_buf[0..avail_len].copy_from_slice(__input);
25047 Bytes::new(&payload_buf)
25048 } else {
25049 Bytes::new(__input)
25050 };
25051 let mut __struct = Self::default();
25052 __struct.time_usec = buf.get_u64_le();
25053 __struct.roll = buf.get_f32_le();
25054 __struct.pitch = buf.get_f32_le();
25055 __struct.yaw = buf.get_f32_le();
25056 __struct.rollspeed = buf.get_f32_le();
25057 __struct.pitchspeed = buf.get_f32_le();
25058 __struct.yawspeed = buf.get_f32_le();
25059 __struct.lat = buf.get_i32_le();
25060 __struct.lon = buf.get_i32_le();
25061 __struct.alt = buf.get_i32_le();
25062 __struct.vx = buf.get_i16_le();
25063 __struct.vy = buf.get_i16_le();
25064 __struct.vz = buf.get_i16_le();
25065 __struct.xacc = buf.get_i16_le();
25066 __struct.yacc = buf.get_i16_le();
25067 __struct.zacc = buf.get_i16_le();
25068 Ok(__struct)
25069 }
25070 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25071 let mut __tmp = BytesMut::new(bytes);
25072 #[allow(clippy::absurd_extreme_comparisons)]
25073 #[allow(unused_comparisons)]
25074 if __tmp.remaining() < Self::ENCODED_LEN {
25075 panic!(
25076 "buffer is too small (need {} bytes, but got {})",
25077 Self::ENCODED_LEN,
25078 __tmp.remaining(),
25079 )
25080 }
25081 __tmp.put_u64_le(self.time_usec);
25082 __tmp.put_f32_le(self.roll);
25083 __tmp.put_f32_le(self.pitch);
25084 __tmp.put_f32_le(self.yaw);
25085 __tmp.put_f32_le(self.rollspeed);
25086 __tmp.put_f32_le(self.pitchspeed);
25087 __tmp.put_f32_le(self.yawspeed);
25088 __tmp.put_i32_le(self.lat);
25089 __tmp.put_i32_le(self.lon);
25090 __tmp.put_i32_le(self.alt);
25091 __tmp.put_i16_le(self.vx);
25092 __tmp.put_i16_le(self.vy);
25093 __tmp.put_i16_le(self.vz);
25094 __tmp.put_i16_le(self.xacc);
25095 __tmp.put_i16_le(self.yacc);
25096 __tmp.put_i16_le(self.zacc);
25097 if matches!(version, MavlinkVersion::V2) {
25098 let len = __tmp.len();
25099 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25100 } else {
25101 __tmp.len()
25102 }
25103 }
25104}
25105#[doc = "id: 2"]
25106#[doc = "The system time is the time of the master clock. This can be emitted by flight controllers, onboard computers, or other components in the MAVLink network. Components that are using a less reliable time source, such as a battery-backed real time clock, can choose to match their system clock to that of a SYSTEM_TYPE that indicates a more recent time. This allows more broadly accurate date stamping of logs, and so on. If precise time synchronization is needed then use TIMESYNC instead."]
25107#[derive(Debug, Clone, PartialEq)]
25108#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25109#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25110pub struct SYSTEM_TIME_DATA {
25111 #[doc = "Timestamp (UNIX epoch time)."]
25112 pub time_unix_usec: u64,
25113 #[doc = "Timestamp (time since system boot)."]
25114 pub time_boot_ms: u32,
25115}
25116impl SYSTEM_TIME_DATA {
25117 pub const ENCODED_LEN: usize = 12usize;
25118 pub const DEFAULT: Self = Self {
25119 time_unix_usec: 0_u64,
25120 time_boot_ms: 0_u32,
25121 };
25122 #[cfg(feature = "arbitrary")]
25123 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25124 use arbitrary::{Arbitrary, Unstructured};
25125 let mut buf = [0u8; 1024];
25126 rng.fill_bytes(&mut buf);
25127 let mut unstructured = Unstructured::new(&buf);
25128 Self::arbitrary(&mut unstructured).unwrap_or_default()
25129 }
25130}
25131impl Default for SYSTEM_TIME_DATA {
25132 fn default() -> Self {
25133 Self::DEFAULT.clone()
25134 }
25135}
25136impl MessageData for SYSTEM_TIME_DATA {
25137 type Message = MavMessage;
25138 const ID: u32 = 2u32;
25139 const NAME: &'static str = "SYSTEM_TIME";
25140 const EXTRA_CRC: u8 = 137u8;
25141 const ENCODED_LEN: usize = 12usize;
25142 fn deser(
25143 _version: MavlinkVersion,
25144 __input: &[u8],
25145 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25146 let avail_len = __input.len();
25147 let mut payload_buf = [0; Self::ENCODED_LEN];
25148 let mut buf = if avail_len < Self::ENCODED_LEN {
25149 payload_buf[0..avail_len].copy_from_slice(__input);
25150 Bytes::new(&payload_buf)
25151 } else {
25152 Bytes::new(__input)
25153 };
25154 let mut __struct = Self::default();
25155 __struct.time_unix_usec = buf.get_u64_le();
25156 __struct.time_boot_ms = buf.get_u32_le();
25157 Ok(__struct)
25158 }
25159 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25160 let mut __tmp = BytesMut::new(bytes);
25161 #[allow(clippy::absurd_extreme_comparisons)]
25162 #[allow(unused_comparisons)]
25163 if __tmp.remaining() < Self::ENCODED_LEN {
25164 panic!(
25165 "buffer is too small (need {} bytes, but got {})",
25166 Self::ENCODED_LEN,
25167 __tmp.remaining(),
25168 )
25169 }
25170 __tmp.put_u64_le(self.time_unix_usec);
25171 __tmp.put_u32_le(self.time_boot_ms);
25172 if matches!(version, MavlinkVersion::V2) {
25173 let len = __tmp.len();
25174 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25175 } else {
25176 __tmp.len()
25177 }
25178 }
25179}
25180#[doc = "id: 261"]
25181#[doc = "Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc."]
25182#[derive(Debug, Clone, PartialEq)]
25183#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25184#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25185pub struct STORAGE_INFORMATION_DATA {
25186 #[doc = "Timestamp (time since system boot)."]
25187 pub time_boot_ms: u32,
25188 #[doc = "Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
25189 pub total_capacity: f32,
25190 #[doc = "Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
25191 pub used_capacity: f32,
25192 #[doc = "Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
25193 pub available_capacity: f32,
25194 #[doc = "Read speed."]
25195 pub read_speed: f32,
25196 #[doc = "Write speed."]
25197 pub write_speed: f32,
25198 #[doc = "Storage ID (1 for first, 2 for second, etc.)"]
25199 pub storage_id: u8,
25200 #[doc = "Number of storage devices"]
25201 pub storage_count: u8,
25202 #[doc = "Status of storage"]
25203 pub status: StorageStatus,
25204 #[doc = "Type of storage"]
25205 #[cfg_attr(feature = "serde", serde(default))]
25206 pub mavtype: StorageType,
25207 #[doc = "Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user."]
25208 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25209 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
25210 pub name: [u8; 32],
25211 #[doc = "Flags indicating whether this instance is preferred storage for photos, videos, etc. Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types."]
25212 #[cfg_attr(feature = "serde", serde(default))]
25213 pub storage_usage: StorageUsageFlag,
25214}
25215impl STORAGE_INFORMATION_DATA {
25216 pub const ENCODED_LEN: usize = 61usize;
25217 pub const DEFAULT: Self = Self {
25218 time_boot_ms: 0_u32,
25219 total_capacity: 0.0_f32,
25220 used_capacity: 0.0_f32,
25221 available_capacity: 0.0_f32,
25222 read_speed: 0.0_f32,
25223 write_speed: 0.0_f32,
25224 storage_id: 0_u8,
25225 storage_count: 0_u8,
25226 status: StorageStatus::DEFAULT,
25227 mavtype: StorageType::DEFAULT,
25228 name: [0_u8; 32usize],
25229 storage_usage: StorageUsageFlag::DEFAULT,
25230 };
25231 #[cfg(feature = "arbitrary")]
25232 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25233 use arbitrary::{Arbitrary, Unstructured};
25234 let mut buf = [0u8; 1024];
25235 rng.fill_bytes(&mut buf);
25236 let mut unstructured = Unstructured::new(&buf);
25237 Self::arbitrary(&mut unstructured).unwrap_or_default()
25238 }
25239}
25240impl Default for STORAGE_INFORMATION_DATA {
25241 fn default() -> Self {
25242 Self::DEFAULT.clone()
25243 }
25244}
25245impl MessageData for STORAGE_INFORMATION_DATA {
25246 type Message = MavMessage;
25247 const ID: u32 = 261u32;
25248 const NAME: &'static str = "STORAGE_INFORMATION";
25249 const EXTRA_CRC: u8 = 179u8;
25250 const ENCODED_LEN: usize = 61usize;
25251 fn deser(
25252 _version: MavlinkVersion,
25253 __input: &[u8],
25254 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25255 let avail_len = __input.len();
25256 let mut payload_buf = [0; Self::ENCODED_LEN];
25257 let mut buf = if avail_len < Self::ENCODED_LEN {
25258 payload_buf[0..avail_len].copy_from_slice(__input);
25259 Bytes::new(&payload_buf)
25260 } else {
25261 Bytes::new(__input)
25262 };
25263 let mut __struct = Self::default();
25264 __struct.time_boot_ms = buf.get_u32_le();
25265 __struct.total_capacity = buf.get_f32_le();
25266 __struct.used_capacity = buf.get_f32_le();
25267 __struct.available_capacity = buf.get_f32_le();
25268 __struct.read_speed = buf.get_f32_le();
25269 __struct.write_speed = buf.get_f32_le();
25270 __struct.storage_id = buf.get_u8();
25271 __struct.storage_count = buf.get_u8();
25272 let tmp = buf.get_u8();
25273 __struct.status =
25274 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25275 enum_type: "StorageStatus",
25276 value: tmp as u32,
25277 })?;
25278 let tmp = buf.get_u8();
25279 __struct.mavtype =
25280 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25281 enum_type: "StorageType",
25282 value: tmp as u32,
25283 })?;
25284 for v in &mut __struct.name {
25285 let val = buf.get_u8();
25286 *v = val;
25287 }
25288 let tmp = buf.get_u8();
25289 __struct.storage_usage = StorageUsageFlag::from_bits(tmp & StorageUsageFlag::all().bits())
25290 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
25291 flag_type: "StorageUsageFlag",
25292 value: tmp as u32,
25293 })?;
25294 Ok(__struct)
25295 }
25296 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25297 let mut __tmp = BytesMut::new(bytes);
25298 #[allow(clippy::absurd_extreme_comparisons)]
25299 #[allow(unused_comparisons)]
25300 if __tmp.remaining() < Self::ENCODED_LEN {
25301 panic!(
25302 "buffer is too small (need {} bytes, but got {})",
25303 Self::ENCODED_LEN,
25304 __tmp.remaining(),
25305 )
25306 }
25307 __tmp.put_u32_le(self.time_boot_ms);
25308 __tmp.put_f32_le(self.total_capacity);
25309 __tmp.put_f32_le(self.used_capacity);
25310 __tmp.put_f32_le(self.available_capacity);
25311 __tmp.put_f32_le(self.read_speed);
25312 __tmp.put_f32_le(self.write_speed);
25313 __tmp.put_u8(self.storage_id);
25314 __tmp.put_u8(self.storage_count);
25315 __tmp.put_u8(self.status as u8);
25316 __tmp.put_u8(self.mavtype as u8);
25317 for val in &self.name {
25318 __tmp.put_u8(*val);
25319 }
25320 __tmp.put_u8(self.storage_usage.bits());
25321 if matches!(version, MavlinkVersion::V2) {
25322 let len = __tmp.len();
25323 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25324 } else {
25325 __tmp.len()
25326 }
25327 }
25328}
25329#[doc = "id: 372"]
25330#[doc = "Battery information that is static, or requires infrequent update. This message should requested using MAV_CMD_REQUEST_MESSAGE and/or streamed at very low rate. BATTERY_STATUS_V2 is used for higher-rate battery status information."]
25331#[derive(Debug, Clone, PartialEq)]
25332#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25333#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25334pub struct BATTERY_INFO_DATA {
25335 #[doc = "Minimum per-cell voltage when discharging. 0: field not provided."]
25336 pub discharge_minimum_voltage: f32,
25337 #[doc = "Minimum per-cell voltage when charging. 0: field not provided."]
25338 pub charging_minimum_voltage: f32,
25339 #[doc = "Minimum per-cell voltage when resting. 0: field not provided."]
25340 pub resting_minimum_voltage: f32,
25341 #[doc = "Maximum per-cell voltage when charged. 0: field not provided."]
25342 pub charging_maximum_voltage: f32,
25343 #[doc = "Maximum pack continuous charge current. 0: field not provided."]
25344 pub charging_maximum_current: f32,
25345 #[doc = "Battery nominal voltage. Used for conversion between Wh and Ah. 0: field not provided."]
25346 pub nominal_voltage: f32,
25347 #[doc = "Maximum pack discharge current. 0: field not provided."]
25348 pub discharge_maximum_current: f32,
25349 #[doc = "Maximum pack discharge burst current. 0: field not provided."]
25350 pub discharge_maximum_burst_current: f32,
25351 #[doc = "Fully charged design capacity. 0: field not provided."]
25352 pub design_capacity: f32,
25353 #[doc = "Predicted battery capacity when fully charged (accounting for battery degradation). NAN: field not provided."]
25354 pub full_charge_capacity: f32,
25355 #[doc = "Lifetime count of the number of charge/discharge cycles (<https://en.wikipedia.org/wiki/Charge_cycle>). UINT16_MAX: field not provided."]
25356 pub cycle_count: u16,
25357 #[doc = "Battery weight. 0: field not provided."]
25358 pub weight: u16,
25359 #[doc = "Battery ID"]
25360 pub id: u8,
25361 #[doc = "Function of the battery."]
25362 pub battery_function: MavBatteryFunction,
25363 #[doc = "Type (chemistry) of the battery."]
25364 pub mavtype: MavBatteryType,
25365 #[doc = "State of Health (SOH) estimate. Typically 100% at the time of manufacture and will decrease over time and use. -1: field not provided."]
25366 pub state_of_health: u8,
25367 #[doc = "Number of battery cells in series. 0: field not provided."]
25368 pub cells_in_series: u8,
25369 #[doc = "Manufacture date (DDMMYYYY) in ASCII characters, 0 terminated. All 0: field not provided."]
25370 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
25371 pub manufacture_date: [u8; 9],
25372 #[doc = "Serial number in ASCII characters, 0 terminated. All 0: field not provided."]
25373 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
25374 pub serial_number: [u8; 32],
25375 #[doc = "Battery device name. Formatted as manufacturer name then product name, separated with an underscore (in ASCII characters), 0 terminated. All 0: field not provided."]
25376 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
25377 pub name: [u8; 50],
25378}
25379impl BATTERY_INFO_DATA {
25380 pub const ENCODED_LEN: usize = 140usize;
25381 pub const DEFAULT: Self = Self {
25382 discharge_minimum_voltage: 0.0_f32,
25383 charging_minimum_voltage: 0.0_f32,
25384 resting_minimum_voltage: 0.0_f32,
25385 charging_maximum_voltage: 0.0_f32,
25386 charging_maximum_current: 0.0_f32,
25387 nominal_voltage: 0.0_f32,
25388 discharge_maximum_current: 0.0_f32,
25389 discharge_maximum_burst_current: 0.0_f32,
25390 design_capacity: 0.0_f32,
25391 full_charge_capacity: 0.0_f32,
25392 cycle_count: 0_u16,
25393 weight: 0_u16,
25394 id: 0_u8,
25395 battery_function: MavBatteryFunction::DEFAULT,
25396 mavtype: MavBatteryType::DEFAULT,
25397 state_of_health: 0_u8,
25398 cells_in_series: 0_u8,
25399 manufacture_date: [0_u8; 9usize],
25400 serial_number: [0_u8; 32usize],
25401 name: [0_u8; 50usize],
25402 };
25403 #[cfg(feature = "arbitrary")]
25404 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25405 use arbitrary::{Arbitrary, Unstructured};
25406 let mut buf = [0u8; 1024];
25407 rng.fill_bytes(&mut buf);
25408 let mut unstructured = Unstructured::new(&buf);
25409 Self::arbitrary(&mut unstructured).unwrap_or_default()
25410 }
25411}
25412impl Default for BATTERY_INFO_DATA {
25413 fn default() -> Self {
25414 Self::DEFAULT.clone()
25415 }
25416}
25417impl MessageData for BATTERY_INFO_DATA {
25418 type Message = MavMessage;
25419 const ID: u32 = 372u32;
25420 const NAME: &'static str = "BATTERY_INFO";
25421 const EXTRA_CRC: u8 = 26u8;
25422 const ENCODED_LEN: usize = 140usize;
25423 fn deser(
25424 _version: MavlinkVersion,
25425 __input: &[u8],
25426 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25427 let avail_len = __input.len();
25428 let mut payload_buf = [0; Self::ENCODED_LEN];
25429 let mut buf = if avail_len < Self::ENCODED_LEN {
25430 payload_buf[0..avail_len].copy_from_slice(__input);
25431 Bytes::new(&payload_buf)
25432 } else {
25433 Bytes::new(__input)
25434 };
25435 let mut __struct = Self::default();
25436 __struct.discharge_minimum_voltage = buf.get_f32_le();
25437 __struct.charging_minimum_voltage = buf.get_f32_le();
25438 __struct.resting_minimum_voltage = buf.get_f32_le();
25439 __struct.charging_maximum_voltage = buf.get_f32_le();
25440 __struct.charging_maximum_current = buf.get_f32_le();
25441 __struct.nominal_voltage = buf.get_f32_le();
25442 __struct.discharge_maximum_current = buf.get_f32_le();
25443 __struct.discharge_maximum_burst_current = buf.get_f32_le();
25444 __struct.design_capacity = buf.get_f32_le();
25445 __struct.full_charge_capacity = buf.get_f32_le();
25446 __struct.cycle_count = buf.get_u16_le();
25447 __struct.weight = buf.get_u16_le();
25448 __struct.id = buf.get_u8();
25449 let tmp = buf.get_u8();
25450 __struct.battery_function =
25451 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25452 enum_type: "MavBatteryFunction",
25453 value: tmp as u32,
25454 })?;
25455 let tmp = buf.get_u8();
25456 __struct.mavtype =
25457 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25458 enum_type: "MavBatteryType",
25459 value: tmp as u32,
25460 })?;
25461 __struct.state_of_health = buf.get_u8();
25462 __struct.cells_in_series = buf.get_u8();
25463 for v in &mut __struct.manufacture_date {
25464 let val = buf.get_u8();
25465 *v = val;
25466 }
25467 for v in &mut __struct.serial_number {
25468 let val = buf.get_u8();
25469 *v = val;
25470 }
25471 for v in &mut __struct.name {
25472 let val = buf.get_u8();
25473 *v = val;
25474 }
25475 Ok(__struct)
25476 }
25477 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25478 let mut __tmp = BytesMut::new(bytes);
25479 #[allow(clippy::absurd_extreme_comparisons)]
25480 #[allow(unused_comparisons)]
25481 if __tmp.remaining() < Self::ENCODED_LEN {
25482 panic!(
25483 "buffer is too small (need {} bytes, but got {})",
25484 Self::ENCODED_LEN,
25485 __tmp.remaining(),
25486 )
25487 }
25488 __tmp.put_f32_le(self.discharge_minimum_voltage);
25489 __tmp.put_f32_le(self.charging_minimum_voltage);
25490 __tmp.put_f32_le(self.resting_minimum_voltage);
25491 __tmp.put_f32_le(self.charging_maximum_voltage);
25492 __tmp.put_f32_le(self.charging_maximum_current);
25493 __tmp.put_f32_le(self.nominal_voltage);
25494 __tmp.put_f32_le(self.discharge_maximum_current);
25495 __tmp.put_f32_le(self.discharge_maximum_burst_current);
25496 __tmp.put_f32_le(self.design_capacity);
25497 __tmp.put_f32_le(self.full_charge_capacity);
25498 __tmp.put_u16_le(self.cycle_count);
25499 __tmp.put_u16_le(self.weight);
25500 __tmp.put_u8(self.id);
25501 __tmp.put_u8(self.battery_function as u8);
25502 __tmp.put_u8(self.mavtype as u8);
25503 __tmp.put_u8(self.state_of_health);
25504 __tmp.put_u8(self.cells_in_series);
25505 for val in &self.manufacture_date {
25506 __tmp.put_u8(*val);
25507 }
25508 for val in &self.serial_number {
25509 __tmp.put_u8(*val);
25510 }
25511 for val in &self.name {
25512 __tmp.put_u8(*val);
25513 }
25514 if matches!(version, MavlinkVersion::V2) {
25515 let len = __tmp.len();
25516 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25517 } else {
25518 __tmp.len()
25519 }
25520 }
25521}
25522#[doc = "id: 82"]
25523#[doc = "Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system)."]
25524#[derive(Debug, Clone, PartialEq)]
25525#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25526#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25527pub struct SET_ATTITUDE_TARGET_DATA {
25528 #[doc = "Timestamp (time since system boot)."]
25529 pub time_boot_ms: u32,
25530 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) from MAV_FRAME_LOCAL_NED to MAV_FRAME_BODY_FRD"]
25531 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
25532 pub q: [f32; 4],
25533 #[doc = "Body roll rate"]
25534 pub body_roll_rate: f32,
25535 #[doc = "Body pitch rate"]
25536 pub body_pitch_rate: f32,
25537 #[doc = "Body yaw rate"]
25538 pub body_yaw_rate: f32,
25539 #[doc = "Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)"]
25540 pub thrust: f32,
25541 #[doc = "System ID"]
25542 pub target_system: u8,
25543 #[doc = "Component ID"]
25544 pub target_component: u8,
25545 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
25546 pub type_mask: AttitudeTargetTypemask,
25547 #[doc = "3D thrust setpoint in the body NED frame, normalized to -1 .. 1"]
25548 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25549 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
25550 pub thrust_body: [f32; 3],
25551}
25552impl SET_ATTITUDE_TARGET_DATA {
25553 pub const ENCODED_LEN: usize = 51usize;
25554 pub const DEFAULT: Self = Self {
25555 time_boot_ms: 0_u32,
25556 q: [0.0_f32; 4usize],
25557 body_roll_rate: 0.0_f32,
25558 body_pitch_rate: 0.0_f32,
25559 body_yaw_rate: 0.0_f32,
25560 thrust: 0.0_f32,
25561 target_system: 0_u8,
25562 target_component: 0_u8,
25563 type_mask: AttitudeTargetTypemask::DEFAULT,
25564 thrust_body: [0.0_f32; 3usize],
25565 };
25566 #[cfg(feature = "arbitrary")]
25567 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25568 use arbitrary::{Arbitrary, Unstructured};
25569 let mut buf = [0u8; 1024];
25570 rng.fill_bytes(&mut buf);
25571 let mut unstructured = Unstructured::new(&buf);
25572 Self::arbitrary(&mut unstructured).unwrap_or_default()
25573 }
25574}
25575impl Default for SET_ATTITUDE_TARGET_DATA {
25576 fn default() -> Self {
25577 Self::DEFAULT.clone()
25578 }
25579}
25580impl MessageData for SET_ATTITUDE_TARGET_DATA {
25581 type Message = MavMessage;
25582 const ID: u32 = 82u32;
25583 const NAME: &'static str = "SET_ATTITUDE_TARGET";
25584 const EXTRA_CRC: u8 = 49u8;
25585 const ENCODED_LEN: usize = 51usize;
25586 fn deser(
25587 _version: MavlinkVersion,
25588 __input: &[u8],
25589 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25590 let avail_len = __input.len();
25591 let mut payload_buf = [0; Self::ENCODED_LEN];
25592 let mut buf = if avail_len < Self::ENCODED_LEN {
25593 payload_buf[0..avail_len].copy_from_slice(__input);
25594 Bytes::new(&payload_buf)
25595 } else {
25596 Bytes::new(__input)
25597 };
25598 let mut __struct = Self::default();
25599 __struct.time_boot_ms = buf.get_u32_le();
25600 for v in &mut __struct.q {
25601 let val = buf.get_f32_le();
25602 *v = val;
25603 }
25604 __struct.body_roll_rate = buf.get_f32_le();
25605 __struct.body_pitch_rate = buf.get_f32_le();
25606 __struct.body_yaw_rate = buf.get_f32_le();
25607 __struct.thrust = buf.get_f32_le();
25608 __struct.target_system = buf.get_u8();
25609 __struct.target_component = buf.get_u8();
25610 let tmp = buf.get_u8();
25611 __struct.type_mask = AttitudeTargetTypemask::from_bits(
25612 tmp & AttitudeTargetTypemask::all().bits(),
25613 )
25614 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
25615 flag_type: "AttitudeTargetTypemask",
25616 value: tmp as u32,
25617 })?;
25618 for v in &mut __struct.thrust_body {
25619 let val = buf.get_f32_le();
25620 *v = val;
25621 }
25622 Ok(__struct)
25623 }
25624 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25625 let mut __tmp = BytesMut::new(bytes);
25626 #[allow(clippy::absurd_extreme_comparisons)]
25627 #[allow(unused_comparisons)]
25628 if __tmp.remaining() < Self::ENCODED_LEN {
25629 panic!(
25630 "buffer is too small (need {} bytes, but got {})",
25631 Self::ENCODED_LEN,
25632 __tmp.remaining(),
25633 )
25634 }
25635 __tmp.put_u32_le(self.time_boot_ms);
25636 for val in &self.q {
25637 __tmp.put_f32_le(*val);
25638 }
25639 __tmp.put_f32_le(self.body_roll_rate);
25640 __tmp.put_f32_le(self.body_pitch_rate);
25641 __tmp.put_f32_le(self.body_yaw_rate);
25642 __tmp.put_f32_le(self.thrust);
25643 __tmp.put_u8(self.target_system);
25644 __tmp.put_u8(self.target_component);
25645 __tmp.put_u8(self.type_mask.bits());
25646 for val in &self.thrust_body {
25647 __tmp.put_f32_le(*val);
25648 }
25649 if matches!(version, MavlinkVersion::V2) {
25650 let len = __tmp.len();
25651 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25652 } else {
25653 __tmp.len()
25654 }
25655 }
25656}
25657#[doc = "id: 92"]
25658#[doc = "Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification."]
25659#[derive(Debug, Clone, PartialEq)]
25660#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25661#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25662pub struct HIL_RC_INPUTS_RAW_DATA {
25663 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
25664 pub time_usec: u64,
25665 #[doc = "RC channel 1 value"]
25666 pub chan1_raw: u16,
25667 #[doc = "RC channel 2 value"]
25668 pub chan2_raw: u16,
25669 #[doc = "RC channel 3 value"]
25670 pub chan3_raw: u16,
25671 #[doc = "RC channel 4 value"]
25672 pub chan4_raw: u16,
25673 #[doc = "RC channel 5 value"]
25674 pub chan5_raw: u16,
25675 #[doc = "RC channel 6 value"]
25676 pub chan6_raw: u16,
25677 #[doc = "RC channel 7 value"]
25678 pub chan7_raw: u16,
25679 #[doc = "RC channel 8 value"]
25680 pub chan8_raw: u16,
25681 #[doc = "RC channel 9 value"]
25682 pub chan9_raw: u16,
25683 #[doc = "RC channel 10 value"]
25684 pub chan10_raw: u16,
25685 #[doc = "RC channel 11 value"]
25686 pub chan11_raw: u16,
25687 #[doc = "RC channel 12 value"]
25688 pub chan12_raw: u16,
25689 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
25690 pub rssi: u8,
25691}
25692impl HIL_RC_INPUTS_RAW_DATA {
25693 pub const ENCODED_LEN: usize = 33usize;
25694 pub const DEFAULT: Self = Self {
25695 time_usec: 0_u64,
25696 chan1_raw: 0_u16,
25697 chan2_raw: 0_u16,
25698 chan3_raw: 0_u16,
25699 chan4_raw: 0_u16,
25700 chan5_raw: 0_u16,
25701 chan6_raw: 0_u16,
25702 chan7_raw: 0_u16,
25703 chan8_raw: 0_u16,
25704 chan9_raw: 0_u16,
25705 chan10_raw: 0_u16,
25706 chan11_raw: 0_u16,
25707 chan12_raw: 0_u16,
25708 rssi: 0_u8,
25709 };
25710 #[cfg(feature = "arbitrary")]
25711 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25712 use arbitrary::{Arbitrary, Unstructured};
25713 let mut buf = [0u8; 1024];
25714 rng.fill_bytes(&mut buf);
25715 let mut unstructured = Unstructured::new(&buf);
25716 Self::arbitrary(&mut unstructured).unwrap_or_default()
25717 }
25718}
25719impl Default for HIL_RC_INPUTS_RAW_DATA {
25720 fn default() -> Self {
25721 Self::DEFAULT.clone()
25722 }
25723}
25724impl MessageData for HIL_RC_INPUTS_RAW_DATA {
25725 type Message = MavMessage;
25726 const ID: u32 = 92u32;
25727 const NAME: &'static str = "HIL_RC_INPUTS_RAW";
25728 const EXTRA_CRC: u8 = 54u8;
25729 const ENCODED_LEN: usize = 33usize;
25730 fn deser(
25731 _version: MavlinkVersion,
25732 __input: &[u8],
25733 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25734 let avail_len = __input.len();
25735 let mut payload_buf = [0; Self::ENCODED_LEN];
25736 let mut buf = if avail_len < Self::ENCODED_LEN {
25737 payload_buf[0..avail_len].copy_from_slice(__input);
25738 Bytes::new(&payload_buf)
25739 } else {
25740 Bytes::new(__input)
25741 };
25742 let mut __struct = Self::default();
25743 __struct.time_usec = buf.get_u64_le();
25744 __struct.chan1_raw = buf.get_u16_le();
25745 __struct.chan2_raw = buf.get_u16_le();
25746 __struct.chan3_raw = buf.get_u16_le();
25747 __struct.chan4_raw = buf.get_u16_le();
25748 __struct.chan5_raw = buf.get_u16_le();
25749 __struct.chan6_raw = buf.get_u16_le();
25750 __struct.chan7_raw = buf.get_u16_le();
25751 __struct.chan8_raw = buf.get_u16_le();
25752 __struct.chan9_raw = buf.get_u16_le();
25753 __struct.chan10_raw = buf.get_u16_le();
25754 __struct.chan11_raw = buf.get_u16_le();
25755 __struct.chan12_raw = buf.get_u16_le();
25756 __struct.rssi = buf.get_u8();
25757 Ok(__struct)
25758 }
25759 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25760 let mut __tmp = BytesMut::new(bytes);
25761 #[allow(clippy::absurd_extreme_comparisons)]
25762 #[allow(unused_comparisons)]
25763 if __tmp.remaining() < Self::ENCODED_LEN {
25764 panic!(
25765 "buffer is too small (need {} bytes, but got {})",
25766 Self::ENCODED_LEN,
25767 __tmp.remaining(),
25768 )
25769 }
25770 __tmp.put_u64_le(self.time_usec);
25771 __tmp.put_u16_le(self.chan1_raw);
25772 __tmp.put_u16_le(self.chan2_raw);
25773 __tmp.put_u16_le(self.chan3_raw);
25774 __tmp.put_u16_le(self.chan4_raw);
25775 __tmp.put_u16_le(self.chan5_raw);
25776 __tmp.put_u16_le(self.chan6_raw);
25777 __tmp.put_u16_le(self.chan7_raw);
25778 __tmp.put_u16_le(self.chan8_raw);
25779 __tmp.put_u16_le(self.chan9_raw);
25780 __tmp.put_u16_le(self.chan10_raw);
25781 __tmp.put_u16_le(self.chan11_raw);
25782 __tmp.put_u16_le(self.chan12_raw);
25783 __tmp.put_u8(self.rssi);
25784 if matches!(version, MavlinkVersion::V2) {
25785 let len = __tmp.len();
25786 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25787 } else {
25788 __tmp.len()
25789 }
25790 }
25791}
25792#[doc = "id: 112"]
25793#[doc = "Camera-IMU triggering and synchronisation message."]
25794#[derive(Debug, Clone, PartialEq)]
25795#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25796#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25797pub struct CAMERA_TRIGGER_DATA {
25798 #[doc = "Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
25799 pub time_usec: u64,
25800 #[doc = "Image frame sequence"]
25801 pub seq: u32,
25802}
25803impl CAMERA_TRIGGER_DATA {
25804 pub const ENCODED_LEN: usize = 12usize;
25805 pub const DEFAULT: Self = Self {
25806 time_usec: 0_u64,
25807 seq: 0_u32,
25808 };
25809 #[cfg(feature = "arbitrary")]
25810 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25811 use arbitrary::{Arbitrary, Unstructured};
25812 let mut buf = [0u8; 1024];
25813 rng.fill_bytes(&mut buf);
25814 let mut unstructured = Unstructured::new(&buf);
25815 Self::arbitrary(&mut unstructured).unwrap_or_default()
25816 }
25817}
25818impl Default for CAMERA_TRIGGER_DATA {
25819 fn default() -> Self {
25820 Self::DEFAULT.clone()
25821 }
25822}
25823impl MessageData for CAMERA_TRIGGER_DATA {
25824 type Message = MavMessage;
25825 const ID: u32 = 112u32;
25826 const NAME: &'static str = "CAMERA_TRIGGER";
25827 const EXTRA_CRC: u8 = 174u8;
25828 const ENCODED_LEN: usize = 12usize;
25829 fn deser(
25830 _version: MavlinkVersion,
25831 __input: &[u8],
25832 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25833 let avail_len = __input.len();
25834 let mut payload_buf = [0; Self::ENCODED_LEN];
25835 let mut buf = if avail_len < Self::ENCODED_LEN {
25836 payload_buf[0..avail_len].copy_from_slice(__input);
25837 Bytes::new(&payload_buf)
25838 } else {
25839 Bytes::new(__input)
25840 };
25841 let mut __struct = Self::default();
25842 __struct.time_usec = buf.get_u64_le();
25843 __struct.seq = buf.get_u32_le();
25844 Ok(__struct)
25845 }
25846 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25847 let mut __tmp = BytesMut::new(bytes);
25848 #[allow(clippy::absurd_extreme_comparisons)]
25849 #[allow(unused_comparisons)]
25850 if __tmp.remaining() < Self::ENCODED_LEN {
25851 panic!(
25852 "buffer is too small (need {} bytes, but got {})",
25853 Self::ENCODED_LEN,
25854 __tmp.remaining(),
25855 )
25856 }
25857 __tmp.put_u64_le(self.time_usec);
25858 __tmp.put_u32_le(self.seq);
25859 if matches!(version, MavlinkVersion::V2) {
25860 let len = __tmp.len();
25861 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25862 } else {
25863 __tmp.len()
25864 }
25865 }
25866}
25867#[doc = "id: 380"]
25868#[doc = "Time/duration estimates for various events and actions given the current vehicle state and position."]
25869#[derive(Debug, Clone, PartialEq)]
25870#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25871#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25872pub struct TIME_ESTIMATE_TO_TARGET_DATA {
25873 #[doc = "Estimated time to complete the vehicle's configured \"safe return\" action from its current position (e.g. RTL, Smart RTL, etc.). -1 indicates that the vehicle is landed, or that no time estimate available."]
25874 pub safe_return: i32,
25875 #[doc = "Estimated time for vehicle to complete the LAND action from its current position. -1 indicates that the vehicle is landed, or that no time estimate available."]
25876 pub land: i32,
25877 #[doc = "Estimated time for reaching/completing the currently active mission item. -1 means no time estimate available."]
25878 pub mission_next_item: i32,
25879 #[doc = "Estimated time for completing the current mission. -1 means no mission active and/or no estimate available."]
25880 pub mission_end: i32,
25881 #[doc = "Estimated time for completing the current commanded action (i.e. Go To, Takeoff, Land, etc.). -1 means no action active and/or no estimate available."]
25882 pub commanded_action: i32,
25883}
25884impl TIME_ESTIMATE_TO_TARGET_DATA {
25885 pub const ENCODED_LEN: usize = 20usize;
25886 pub const DEFAULT: Self = Self {
25887 safe_return: 0_i32,
25888 land: 0_i32,
25889 mission_next_item: 0_i32,
25890 mission_end: 0_i32,
25891 commanded_action: 0_i32,
25892 };
25893 #[cfg(feature = "arbitrary")]
25894 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25895 use arbitrary::{Arbitrary, Unstructured};
25896 let mut buf = [0u8; 1024];
25897 rng.fill_bytes(&mut buf);
25898 let mut unstructured = Unstructured::new(&buf);
25899 Self::arbitrary(&mut unstructured).unwrap_or_default()
25900 }
25901}
25902impl Default for TIME_ESTIMATE_TO_TARGET_DATA {
25903 fn default() -> Self {
25904 Self::DEFAULT.clone()
25905 }
25906}
25907impl MessageData for TIME_ESTIMATE_TO_TARGET_DATA {
25908 type Message = MavMessage;
25909 const ID: u32 = 380u32;
25910 const NAME: &'static str = "TIME_ESTIMATE_TO_TARGET";
25911 const EXTRA_CRC: u8 = 232u8;
25912 const ENCODED_LEN: usize = 20usize;
25913 fn deser(
25914 _version: MavlinkVersion,
25915 __input: &[u8],
25916 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25917 let avail_len = __input.len();
25918 let mut payload_buf = [0; Self::ENCODED_LEN];
25919 let mut buf = if avail_len < Self::ENCODED_LEN {
25920 payload_buf[0..avail_len].copy_from_slice(__input);
25921 Bytes::new(&payload_buf)
25922 } else {
25923 Bytes::new(__input)
25924 };
25925 let mut __struct = Self::default();
25926 __struct.safe_return = buf.get_i32_le();
25927 __struct.land = buf.get_i32_le();
25928 __struct.mission_next_item = buf.get_i32_le();
25929 __struct.mission_end = buf.get_i32_le();
25930 __struct.commanded_action = buf.get_i32_le();
25931 Ok(__struct)
25932 }
25933 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25934 let mut __tmp = BytesMut::new(bytes);
25935 #[allow(clippy::absurd_extreme_comparisons)]
25936 #[allow(unused_comparisons)]
25937 if __tmp.remaining() < Self::ENCODED_LEN {
25938 panic!(
25939 "buffer is too small (need {} bytes, but got {})",
25940 Self::ENCODED_LEN,
25941 __tmp.remaining(),
25942 )
25943 }
25944 __tmp.put_i32_le(self.safe_return);
25945 __tmp.put_i32_le(self.land);
25946 __tmp.put_i32_le(self.mission_next_item);
25947 __tmp.put_i32_le(self.mission_end);
25948 __tmp.put_i32_le(self.commanded_action);
25949 if matches!(version, MavlinkVersion::V2) {
25950 let len = __tmp.len();
25951 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25952 } else {
25953 __tmp.len()
25954 }
25955 }
25956}
25957#[doc = "id: 107"]
25958#[doc = "The IMU readings in SI units in NED body frame."]
25959#[derive(Debug, Clone, PartialEq)]
25960#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25961#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25962pub struct HIL_SENSOR_DATA {
25963 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
25964 pub time_usec: u64,
25965 #[doc = "X acceleration"]
25966 pub xacc: f32,
25967 #[doc = "Y acceleration"]
25968 pub yacc: f32,
25969 #[doc = "Z acceleration"]
25970 pub zacc: f32,
25971 #[doc = "Angular speed around X axis in body frame"]
25972 pub xgyro: f32,
25973 #[doc = "Angular speed around Y axis in body frame"]
25974 pub ygyro: f32,
25975 #[doc = "Angular speed around Z axis in body frame"]
25976 pub zgyro: f32,
25977 #[doc = "X Magnetic field"]
25978 pub xmag: f32,
25979 #[doc = "Y Magnetic field"]
25980 pub ymag: f32,
25981 #[doc = "Z Magnetic field"]
25982 pub zmag: f32,
25983 #[doc = "Absolute pressure"]
25984 pub abs_pressure: f32,
25985 #[doc = "Differential pressure (airspeed)"]
25986 pub diff_pressure: f32,
25987 #[doc = "Altitude calculated from pressure"]
25988 pub pressure_alt: f32,
25989 #[doc = "Temperature"]
25990 pub temperature: f32,
25991 #[doc = "Bitmap for fields that have updated since last message"]
25992 pub fields_updated: HilSensorUpdatedFlags,
25993 #[doc = "Sensor ID (zero indexed). Used for multiple sensor inputs"]
25994 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25995 pub id: u8,
25996}
25997impl HIL_SENSOR_DATA {
25998 pub const ENCODED_LEN: usize = 65usize;
25999 pub const DEFAULT: Self = Self {
26000 time_usec: 0_u64,
26001 xacc: 0.0_f32,
26002 yacc: 0.0_f32,
26003 zacc: 0.0_f32,
26004 xgyro: 0.0_f32,
26005 ygyro: 0.0_f32,
26006 zgyro: 0.0_f32,
26007 xmag: 0.0_f32,
26008 ymag: 0.0_f32,
26009 zmag: 0.0_f32,
26010 abs_pressure: 0.0_f32,
26011 diff_pressure: 0.0_f32,
26012 pressure_alt: 0.0_f32,
26013 temperature: 0.0_f32,
26014 fields_updated: HilSensorUpdatedFlags::DEFAULT,
26015 id: 0_u8,
26016 };
26017 #[cfg(feature = "arbitrary")]
26018 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26019 use arbitrary::{Arbitrary, Unstructured};
26020 let mut buf = [0u8; 1024];
26021 rng.fill_bytes(&mut buf);
26022 let mut unstructured = Unstructured::new(&buf);
26023 Self::arbitrary(&mut unstructured).unwrap_or_default()
26024 }
26025}
26026impl Default for HIL_SENSOR_DATA {
26027 fn default() -> Self {
26028 Self::DEFAULT.clone()
26029 }
26030}
26031impl MessageData for HIL_SENSOR_DATA {
26032 type Message = MavMessage;
26033 const ID: u32 = 107u32;
26034 const NAME: &'static str = "HIL_SENSOR";
26035 const EXTRA_CRC: u8 = 108u8;
26036 const ENCODED_LEN: usize = 65usize;
26037 fn deser(
26038 _version: MavlinkVersion,
26039 __input: &[u8],
26040 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26041 let avail_len = __input.len();
26042 let mut payload_buf = [0; Self::ENCODED_LEN];
26043 let mut buf = if avail_len < Self::ENCODED_LEN {
26044 payload_buf[0..avail_len].copy_from_slice(__input);
26045 Bytes::new(&payload_buf)
26046 } else {
26047 Bytes::new(__input)
26048 };
26049 let mut __struct = Self::default();
26050 __struct.time_usec = buf.get_u64_le();
26051 __struct.xacc = buf.get_f32_le();
26052 __struct.yacc = buf.get_f32_le();
26053 __struct.zacc = buf.get_f32_le();
26054 __struct.xgyro = buf.get_f32_le();
26055 __struct.ygyro = buf.get_f32_le();
26056 __struct.zgyro = buf.get_f32_le();
26057 __struct.xmag = buf.get_f32_le();
26058 __struct.ymag = buf.get_f32_le();
26059 __struct.zmag = buf.get_f32_le();
26060 __struct.abs_pressure = buf.get_f32_le();
26061 __struct.diff_pressure = buf.get_f32_le();
26062 __struct.pressure_alt = buf.get_f32_le();
26063 __struct.temperature = buf.get_f32_le();
26064 let tmp = buf.get_u32_le();
26065 __struct.fields_updated = HilSensorUpdatedFlags::from_bits(
26066 tmp & HilSensorUpdatedFlags::all().bits(),
26067 )
26068 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
26069 flag_type: "HilSensorUpdatedFlags",
26070 value: tmp as u32,
26071 })?;
26072 __struct.id = buf.get_u8();
26073 Ok(__struct)
26074 }
26075 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26076 let mut __tmp = BytesMut::new(bytes);
26077 #[allow(clippy::absurd_extreme_comparisons)]
26078 #[allow(unused_comparisons)]
26079 if __tmp.remaining() < Self::ENCODED_LEN {
26080 panic!(
26081 "buffer is too small (need {} bytes, but got {})",
26082 Self::ENCODED_LEN,
26083 __tmp.remaining(),
26084 )
26085 }
26086 __tmp.put_u64_le(self.time_usec);
26087 __tmp.put_f32_le(self.xacc);
26088 __tmp.put_f32_le(self.yacc);
26089 __tmp.put_f32_le(self.zacc);
26090 __tmp.put_f32_le(self.xgyro);
26091 __tmp.put_f32_le(self.ygyro);
26092 __tmp.put_f32_le(self.zgyro);
26093 __tmp.put_f32_le(self.xmag);
26094 __tmp.put_f32_le(self.ymag);
26095 __tmp.put_f32_le(self.zmag);
26096 __tmp.put_f32_le(self.abs_pressure);
26097 __tmp.put_f32_le(self.diff_pressure);
26098 __tmp.put_f32_le(self.pressure_alt);
26099 __tmp.put_f32_le(self.temperature);
26100 __tmp.put_u32_le(self.fields_updated.bits());
26101 __tmp.put_u8(self.id);
26102 if matches!(version, MavlinkVersion::V2) {
26103 let len = __tmp.len();
26104 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26105 } else {
26106 __tmp.len()
26107 }
26108 }
26109}
26110#[doc = "id: 51"]
26111#[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. <https://mavlink.io/en/services/mission.html>."]
26112#[derive(Debug, Clone, PartialEq)]
26113#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26114#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26115pub struct MISSION_REQUEST_INT_DATA {
26116 #[doc = "Sequence"]
26117 pub seq: u16,
26118 #[doc = "System ID"]
26119 pub target_system: u8,
26120 #[doc = "Component ID"]
26121 pub target_component: u8,
26122 #[doc = "Mission type."]
26123 #[cfg_attr(feature = "serde", serde(default))]
26124 pub mission_type: MavMissionType,
26125}
26126impl MISSION_REQUEST_INT_DATA {
26127 pub const ENCODED_LEN: usize = 5usize;
26128 pub const DEFAULT: Self = Self {
26129 seq: 0_u16,
26130 target_system: 0_u8,
26131 target_component: 0_u8,
26132 mission_type: MavMissionType::DEFAULT,
26133 };
26134 #[cfg(feature = "arbitrary")]
26135 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26136 use arbitrary::{Arbitrary, Unstructured};
26137 let mut buf = [0u8; 1024];
26138 rng.fill_bytes(&mut buf);
26139 let mut unstructured = Unstructured::new(&buf);
26140 Self::arbitrary(&mut unstructured).unwrap_or_default()
26141 }
26142}
26143impl Default for MISSION_REQUEST_INT_DATA {
26144 fn default() -> Self {
26145 Self::DEFAULT.clone()
26146 }
26147}
26148impl MessageData for MISSION_REQUEST_INT_DATA {
26149 type Message = MavMessage;
26150 const ID: u32 = 51u32;
26151 const NAME: &'static str = "MISSION_REQUEST_INT";
26152 const EXTRA_CRC: u8 = 196u8;
26153 const ENCODED_LEN: usize = 5usize;
26154 fn deser(
26155 _version: MavlinkVersion,
26156 __input: &[u8],
26157 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26158 let avail_len = __input.len();
26159 let mut payload_buf = [0; Self::ENCODED_LEN];
26160 let mut buf = if avail_len < Self::ENCODED_LEN {
26161 payload_buf[0..avail_len].copy_from_slice(__input);
26162 Bytes::new(&payload_buf)
26163 } else {
26164 Bytes::new(__input)
26165 };
26166 let mut __struct = Self::default();
26167 __struct.seq = buf.get_u16_le();
26168 __struct.target_system = buf.get_u8();
26169 __struct.target_component = buf.get_u8();
26170 let tmp = buf.get_u8();
26171 __struct.mission_type =
26172 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26173 enum_type: "MavMissionType",
26174 value: tmp as u32,
26175 })?;
26176 Ok(__struct)
26177 }
26178 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26179 let mut __tmp = BytesMut::new(bytes);
26180 #[allow(clippy::absurd_extreme_comparisons)]
26181 #[allow(unused_comparisons)]
26182 if __tmp.remaining() < Self::ENCODED_LEN {
26183 panic!(
26184 "buffer is too small (need {} bytes, but got {})",
26185 Self::ENCODED_LEN,
26186 __tmp.remaining(),
26187 )
26188 }
26189 __tmp.put_u16_le(self.seq);
26190 __tmp.put_u8(self.target_system);
26191 __tmp.put_u8(self.target_component);
26192 __tmp.put_u8(self.mission_type as u8);
26193 if matches!(version, MavlinkVersion::V2) {
26194 let len = __tmp.len();
26195 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26196 } else {
26197 __tmp.len()
26198 }
26199 }
26200}
26201#[doc = "id: 136"]
26202#[doc = "Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
26203#[derive(Debug, Clone, PartialEq)]
26204#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26205#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26206pub struct TERRAIN_REPORT_DATA {
26207 #[doc = "Latitude"]
26208 pub lat: i32,
26209 #[doc = "Longitude"]
26210 pub lon: i32,
26211 #[doc = "Terrain height MSL"]
26212 pub terrain_height: f32,
26213 #[doc = "Current vehicle height above lat/lon terrain height"]
26214 pub current_height: f32,
26215 #[doc = "grid spacing (zero if terrain at this location unavailable)"]
26216 pub spacing: u16,
26217 #[doc = "Number of 4x4 terrain blocks waiting to be received or read from disk"]
26218 pub pending: u16,
26219 #[doc = "Number of 4x4 terrain blocks in memory"]
26220 pub loaded: u16,
26221}
26222impl TERRAIN_REPORT_DATA {
26223 pub const ENCODED_LEN: usize = 22usize;
26224 pub const DEFAULT: Self = Self {
26225 lat: 0_i32,
26226 lon: 0_i32,
26227 terrain_height: 0.0_f32,
26228 current_height: 0.0_f32,
26229 spacing: 0_u16,
26230 pending: 0_u16,
26231 loaded: 0_u16,
26232 };
26233 #[cfg(feature = "arbitrary")]
26234 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26235 use arbitrary::{Arbitrary, Unstructured};
26236 let mut buf = [0u8; 1024];
26237 rng.fill_bytes(&mut buf);
26238 let mut unstructured = Unstructured::new(&buf);
26239 Self::arbitrary(&mut unstructured).unwrap_or_default()
26240 }
26241}
26242impl Default for TERRAIN_REPORT_DATA {
26243 fn default() -> Self {
26244 Self::DEFAULT.clone()
26245 }
26246}
26247impl MessageData for TERRAIN_REPORT_DATA {
26248 type Message = MavMessage;
26249 const ID: u32 = 136u32;
26250 const NAME: &'static str = "TERRAIN_REPORT";
26251 const EXTRA_CRC: u8 = 1u8;
26252 const ENCODED_LEN: usize = 22usize;
26253 fn deser(
26254 _version: MavlinkVersion,
26255 __input: &[u8],
26256 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26257 let avail_len = __input.len();
26258 let mut payload_buf = [0; Self::ENCODED_LEN];
26259 let mut buf = if avail_len < Self::ENCODED_LEN {
26260 payload_buf[0..avail_len].copy_from_slice(__input);
26261 Bytes::new(&payload_buf)
26262 } else {
26263 Bytes::new(__input)
26264 };
26265 let mut __struct = Self::default();
26266 __struct.lat = buf.get_i32_le();
26267 __struct.lon = buf.get_i32_le();
26268 __struct.terrain_height = buf.get_f32_le();
26269 __struct.current_height = buf.get_f32_le();
26270 __struct.spacing = buf.get_u16_le();
26271 __struct.pending = buf.get_u16_le();
26272 __struct.loaded = buf.get_u16_le();
26273 Ok(__struct)
26274 }
26275 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26276 let mut __tmp = BytesMut::new(bytes);
26277 #[allow(clippy::absurd_extreme_comparisons)]
26278 #[allow(unused_comparisons)]
26279 if __tmp.remaining() < Self::ENCODED_LEN {
26280 panic!(
26281 "buffer is too small (need {} bytes, but got {})",
26282 Self::ENCODED_LEN,
26283 __tmp.remaining(),
26284 )
26285 }
26286 __tmp.put_i32_le(self.lat);
26287 __tmp.put_i32_le(self.lon);
26288 __tmp.put_f32_le(self.terrain_height);
26289 __tmp.put_f32_le(self.current_height);
26290 __tmp.put_u16_le(self.spacing);
26291 __tmp.put_u16_le(self.pending);
26292 __tmp.put_u16_le(self.loaded);
26293 if matches!(version, MavlinkVersion::V2) {
26294 let len = __tmp.len();
26295 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26296 } else {
26297 __tmp.len()
26298 }
26299 }
26300}
26301#[doc = "id: 147"]
26302#[doc = "Battery information. Updates GCS with flight controller battery status. Smart batteries also use this message, but may additionally send BATTERY_INFO."]
26303#[derive(Debug, Clone, PartialEq)]
26304#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26305#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26306pub struct BATTERY_STATUS_DATA {
26307 #[doc = "Consumed charge, -1: autopilot does not provide consumption estimate"]
26308 pub current_consumed: i32,
26309 #[doc = "Consumed energy, -1: autopilot does not provide energy consumption estimate"]
26310 pub energy_consumed: i32,
26311 #[doc = "Temperature of the battery. INT16_MAX for unknown temperature."]
26312 pub temperature: i16,
26313 #[doc = "Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1)."]
26314 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26315 pub voltages: [u16; 10],
26316 #[doc = "Battery current, -1: autopilot does not measure the current"]
26317 pub current_battery: i16,
26318 #[doc = "Battery ID"]
26319 pub id: u8,
26320 #[doc = "Function of the battery"]
26321 pub battery_function: MavBatteryFunction,
26322 #[doc = "Type (chemistry) of the battery"]
26323 pub mavtype: MavBatteryType,
26324 #[doc = "Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery."]
26325 pub battery_remaining: i8,
26326 #[doc = "Remaining battery time, 0: autopilot does not provide remaining battery time estimate"]
26327 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26328 pub time_remaining: i32,
26329 #[doc = "State for extent of discharge, provided by autopilot for warning or external reactions"]
26330 #[cfg_attr(feature = "serde", serde(default))]
26331 pub charge_state: MavBatteryChargeState,
26332 #[doc = "Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead."]
26333 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26334 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26335 pub voltages_ext: [u16; 4],
26336 #[doc = "Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode."]
26337 #[cfg_attr(feature = "serde", serde(default))]
26338 pub mode: MavBatteryMode,
26339 #[doc = "Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported)."]
26340 #[cfg_attr(feature = "serde", serde(default))]
26341 pub fault_bitmask: MavBatteryFault,
26342}
26343impl BATTERY_STATUS_DATA {
26344 pub const ENCODED_LEN: usize = 54usize;
26345 pub const DEFAULT: Self = Self {
26346 current_consumed: 0_i32,
26347 energy_consumed: 0_i32,
26348 temperature: 0_i16,
26349 voltages: [0_u16; 10usize],
26350 current_battery: 0_i16,
26351 id: 0_u8,
26352 battery_function: MavBatteryFunction::DEFAULT,
26353 mavtype: MavBatteryType::DEFAULT,
26354 battery_remaining: 0_i8,
26355 time_remaining: 0_i32,
26356 charge_state: MavBatteryChargeState::DEFAULT,
26357 voltages_ext: [0_u16; 4usize],
26358 mode: MavBatteryMode::DEFAULT,
26359 fault_bitmask: MavBatteryFault::DEFAULT,
26360 };
26361 #[cfg(feature = "arbitrary")]
26362 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26363 use arbitrary::{Arbitrary, Unstructured};
26364 let mut buf = [0u8; 1024];
26365 rng.fill_bytes(&mut buf);
26366 let mut unstructured = Unstructured::new(&buf);
26367 Self::arbitrary(&mut unstructured).unwrap_or_default()
26368 }
26369}
26370impl Default for BATTERY_STATUS_DATA {
26371 fn default() -> Self {
26372 Self::DEFAULT.clone()
26373 }
26374}
26375impl MessageData for BATTERY_STATUS_DATA {
26376 type Message = MavMessage;
26377 const ID: u32 = 147u32;
26378 const NAME: &'static str = "BATTERY_STATUS";
26379 const EXTRA_CRC: u8 = 154u8;
26380 const ENCODED_LEN: usize = 54usize;
26381 fn deser(
26382 _version: MavlinkVersion,
26383 __input: &[u8],
26384 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26385 let avail_len = __input.len();
26386 let mut payload_buf = [0; Self::ENCODED_LEN];
26387 let mut buf = if avail_len < Self::ENCODED_LEN {
26388 payload_buf[0..avail_len].copy_from_slice(__input);
26389 Bytes::new(&payload_buf)
26390 } else {
26391 Bytes::new(__input)
26392 };
26393 let mut __struct = Self::default();
26394 __struct.current_consumed = buf.get_i32_le();
26395 __struct.energy_consumed = buf.get_i32_le();
26396 __struct.temperature = buf.get_i16_le();
26397 for v in &mut __struct.voltages {
26398 let val = buf.get_u16_le();
26399 *v = val;
26400 }
26401 __struct.current_battery = buf.get_i16_le();
26402 __struct.id = buf.get_u8();
26403 let tmp = buf.get_u8();
26404 __struct.battery_function =
26405 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26406 enum_type: "MavBatteryFunction",
26407 value: tmp as u32,
26408 })?;
26409 let tmp = buf.get_u8();
26410 __struct.mavtype =
26411 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26412 enum_type: "MavBatteryType",
26413 value: tmp as u32,
26414 })?;
26415 __struct.battery_remaining = buf.get_i8();
26416 __struct.time_remaining = buf.get_i32_le();
26417 let tmp = buf.get_u8();
26418 __struct.charge_state =
26419 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26420 enum_type: "MavBatteryChargeState",
26421 value: tmp as u32,
26422 })?;
26423 for v in &mut __struct.voltages_ext {
26424 let val = buf.get_u16_le();
26425 *v = val;
26426 }
26427 let tmp = buf.get_u8();
26428 __struct.mode =
26429 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26430 enum_type: "MavBatteryMode",
26431 value: tmp as u32,
26432 })?;
26433 let tmp = buf.get_u32_le();
26434 __struct.fault_bitmask = MavBatteryFault::from_bits(tmp & MavBatteryFault::all().bits())
26435 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
26436 flag_type: "MavBatteryFault",
26437 value: tmp as u32,
26438 })?;
26439 Ok(__struct)
26440 }
26441 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26442 let mut __tmp = BytesMut::new(bytes);
26443 #[allow(clippy::absurd_extreme_comparisons)]
26444 #[allow(unused_comparisons)]
26445 if __tmp.remaining() < Self::ENCODED_LEN {
26446 panic!(
26447 "buffer is too small (need {} bytes, but got {})",
26448 Self::ENCODED_LEN,
26449 __tmp.remaining(),
26450 )
26451 }
26452 __tmp.put_i32_le(self.current_consumed);
26453 __tmp.put_i32_le(self.energy_consumed);
26454 __tmp.put_i16_le(self.temperature);
26455 for val in &self.voltages {
26456 __tmp.put_u16_le(*val);
26457 }
26458 __tmp.put_i16_le(self.current_battery);
26459 __tmp.put_u8(self.id);
26460 __tmp.put_u8(self.battery_function as u8);
26461 __tmp.put_u8(self.mavtype as u8);
26462 __tmp.put_i8(self.battery_remaining);
26463 __tmp.put_i32_le(self.time_remaining);
26464 __tmp.put_u8(self.charge_state as u8);
26465 for val in &self.voltages_ext {
26466 __tmp.put_u16_le(*val);
26467 }
26468 __tmp.put_u8(self.mode as u8);
26469 __tmp.put_u32_le(self.fault_bitmask.bits());
26470 if matches!(version, MavlinkVersion::V2) {
26471 let len = __tmp.len();
26472 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26473 } else {
26474 __tmp.len()
26475 }
26476 }
26477}
26478#[doc = "id: 24"]
26479#[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate."]
26480#[derive(Debug, Clone, PartialEq)]
26481#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26482#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26483pub struct GPS_RAW_INT_DATA {
26484 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
26485 pub time_usec: u64,
26486 #[doc = "Latitude (WGS84, EGM96 ellipsoid)"]
26487 pub lat: i32,
26488 #[doc = "Longitude (WGS84, EGM96 ellipsoid)"]
26489 pub lon: i32,
26490 #[doc = "Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude."]
26491 pub alt: i32,
26492 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
26493 pub eph: u16,
26494 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
26495 pub epv: u16,
26496 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
26497 pub vel: u16,
26498 #[doc = "Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
26499 pub cog: u16,
26500 #[doc = "GPS fix type."]
26501 pub fix_type: GpsFixType,
26502 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
26503 pub satellites_visible: u8,
26504 #[doc = "Altitude (above WGS84, EGM96 ellipsoid). Positive for up."]
26505 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26506 pub alt_ellipsoid: i32,
26507 #[doc = "Position uncertainty."]
26508 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26509 pub h_acc: u32,
26510 #[doc = "Altitude uncertainty."]
26511 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26512 pub v_acc: u32,
26513 #[doc = "Speed uncertainty."]
26514 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26515 pub vel_acc: u32,
26516 #[doc = "Heading / track uncertainty"]
26517 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26518 pub hdg_acc: u32,
26519 #[doc = "Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north."]
26520 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26521 pub yaw: u16,
26522}
26523impl GPS_RAW_INT_DATA {
26524 pub const ENCODED_LEN: usize = 52usize;
26525 pub const DEFAULT: Self = Self {
26526 time_usec: 0_u64,
26527 lat: 0_i32,
26528 lon: 0_i32,
26529 alt: 0_i32,
26530 eph: 0_u16,
26531 epv: 0_u16,
26532 vel: 0_u16,
26533 cog: 0_u16,
26534 fix_type: GpsFixType::DEFAULT,
26535 satellites_visible: 0_u8,
26536 alt_ellipsoid: 0_i32,
26537 h_acc: 0_u32,
26538 v_acc: 0_u32,
26539 vel_acc: 0_u32,
26540 hdg_acc: 0_u32,
26541 yaw: 0_u16,
26542 };
26543 #[cfg(feature = "arbitrary")]
26544 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26545 use arbitrary::{Arbitrary, Unstructured};
26546 let mut buf = [0u8; 1024];
26547 rng.fill_bytes(&mut buf);
26548 let mut unstructured = Unstructured::new(&buf);
26549 Self::arbitrary(&mut unstructured).unwrap_or_default()
26550 }
26551}
26552impl Default for GPS_RAW_INT_DATA {
26553 fn default() -> Self {
26554 Self::DEFAULT.clone()
26555 }
26556}
26557impl MessageData for GPS_RAW_INT_DATA {
26558 type Message = MavMessage;
26559 const ID: u32 = 24u32;
26560 const NAME: &'static str = "GPS_RAW_INT";
26561 const EXTRA_CRC: u8 = 24u8;
26562 const ENCODED_LEN: usize = 52usize;
26563 fn deser(
26564 _version: MavlinkVersion,
26565 __input: &[u8],
26566 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26567 let avail_len = __input.len();
26568 let mut payload_buf = [0; Self::ENCODED_LEN];
26569 let mut buf = if avail_len < Self::ENCODED_LEN {
26570 payload_buf[0..avail_len].copy_from_slice(__input);
26571 Bytes::new(&payload_buf)
26572 } else {
26573 Bytes::new(__input)
26574 };
26575 let mut __struct = Self::default();
26576 __struct.time_usec = buf.get_u64_le();
26577 __struct.lat = buf.get_i32_le();
26578 __struct.lon = buf.get_i32_le();
26579 __struct.alt = buf.get_i32_le();
26580 __struct.eph = buf.get_u16_le();
26581 __struct.epv = buf.get_u16_le();
26582 __struct.vel = buf.get_u16_le();
26583 __struct.cog = buf.get_u16_le();
26584 let tmp = buf.get_u8();
26585 __struct.fix_type =
26586 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26587 enum_type: "GpsFixType",
26588 value: tmp as u32,
26589 })?;
26590 __struct.satellites_visible = buf.get_u8();
26591 __struct.alt_ellipsoid = buf.get_i32_le();
26592 __struct.h_acc = buf.get_u32_le();
26593 __struct.v_acc = buf.get_u32_le();
26594 __struct.vel_acc = buf.get_u32_le();
26595 __struct.hdg_acc = buf.get_u32_le();
26596 __struct.yaw = buf.get_u16_le();
26597 Ok(__struct)
26598 }
26599 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26600 let mut __tmp = BytesMut::new(bytes);
26601 #[allow(clippy::absurd_extreme_comparisons)]
26602 #[allow(unused_comparisons)]
26603 if __tmp.remaining() < Self::ENCODED_LEN {
26604 panic!(
26605 "buffer is too small (need {} bytes, but got {})",
26606 Self::ENCODED_LEN,
26607 __tmp.remaining(),
26608 )
26609 }
26610 __tmp.put_u64_le(self.time_usec);
26611 __tmp.put_i32_le(self.lat);
26612 __tmp.put_i32_le(self.lon);
26613 __tmp.put_i32_le(self.alt);
26614 __tmp.put_u16_le(self.eph);
26615 __tmp.put_u16_le(self.epv);
26616 __tmp.put_u16_le(self.vel);
26617 __tmp.put_u16_le(self.cog);
26618 __tmp.put_u8(self.fix_type as u8);
26619 __tmp.put_u8(self.satellites_visible);
26620 __tmp.put_i32_le(self.alt_ellipsoid);
26621 __tmp.put_u32_le(self.h_acc);
26622 __tmp.put_u32_le(self.v_acc);
26623 __tmp.put_u32_le(self.vel_acc);
26624 __tmp.put_u32_le(self.hdg_acc);
26625 __tmp.put_u16_le(self.yaw);
26626 if matches!(version, MavlinkVersion::V2) {
26627 let len = __tmp.len();
26628 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26629 } else {
26630 __tmp.len()
26631 }
26632 }
26633}
26634#[doc = "id: 102"]
26635#[doc = "Local position/attitude estimate from a vision source."]
26636#[derive(Debug, Clone, PartialEq)]
26637#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26638#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26639pub struct VISION_POSITION_ESTIMATE_DATA {
26640 #[doc = "Timestamp (UNIX time or time since system boot)"]
26641 pub usec: u64,
26642 #[doc = "Local X position"]
26643 pub x: f32,
26644 #[doc = "Local Y position"]
26645 pub y: f32,
26646 #[doc = "Local Z position"]
26647 pub z: f32,
26648 #[doc = "Roll angle"]
26649 pub roll: f32,
26650 #[doc = "Pitch angle"]
26651 pub pitch: f32,
26652 #[doc = "Yaw angle"]
26653 pub yaw: f32,
26654 #[doc = "Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
26655 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26656 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26657 pub covariance: [f32; 21],
26658 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
26659 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26660 pub reset_counter: u8,
26661}
26662impl VISION_POSITION_ESTIMATE_DATA {
26663 pub const ENCODED_LEN: usize = 117usize;
26664 pub const DEFAULT: Self = Self {
26665 usec: 0_u64,
26666 x: 0.0_f32,
26667 y: 0.0_f32,
26668 z: 0.0_f32,
26669 roll: 0.0_f32,
26670 pitch: 0.0_f32,
26671 yaw: 0.0_f32,
26672 covariance: [0.0_f32; 21usize],
26673 reset_counter: 0_u8,
26674 };
26675 #[cfg(feature = "arbitrary")]
26676 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26677 use arbitrary::{Arbitrary, Unstructured};
26678 let mut buf = [0u8; 1024];
26679 rng.fill_bytes(&mut buf);
26680 let mut unstructured = Unstructured::new(&buf);
26681 Self::arbitrary(&mut unstructured).unwrap_or_default()
26682 }
26683}
26684impl Default for VISION_POSITION_ESTIMATE_DATA {
26685 fn default() -> Self {
26686 Self::DEFAULT.clone()
26687 }
26688}
26689impl MessageData for VISION_POSITION_ESTIMATE_DATA {
26690 type Message = MavMessage;
26691 const ID: u32 = 102u32;
26692 const NAME: &'static str = "VISION_POSITION_ESTIMATE";
26693 const EXTRA_CRC: u8 = 158u8;
26694 const ENCODED_LEN: usize = 117usize;
26695 fn deser(
26696 _version: MavlinkVersion,
26697 __input: &[u8],
26698 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26699 let avail_len = __input.len();
26700 let mut payload_buf = [0; Self::ENCODED_LEN];
26701 let mut buf = if avail_len < Self::ENCODED_LEN {
26702 payload_buf[0..avail_len].copy_from_slice(__input);
26703 Bytes::new(&payload_buf)
26704 } else {
26705 Bytes::new(__input)
26706 };
26707 let mut __struct = Self::default();
26708 __struct.usec = buf.get_u64_le();
26709 __struct.x = buf.get_f32_le();
26710 __struct.y = buf.get_f32_le();
26711 __struct.z = buf.get_f32_le();
26712 __struct.roll = buf.get_f32_le();
26713 __struct.pitch = buf.get_f32_le();
26714 __struct.yaw = buf.get_f32_le();
26715 for v in &mut __struct.covariance {
26716 let val = buf.get_f32_le();
26717 *v = val;
26718 }
26719 __struct.reset_counter = buf.get_u8();
26720 Ok(__struct)
26721 }
26722 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26723 let mut __tmp = BytesMut::new(bytes);
26724 #[allow(clippy::absurd_extreme_comparisons)]
26725 #[allow(unused_comparisons)]
26726 if __tmp.remaining() < Self::ENCODED_LEN {
26727 panic!(
26728 "buffer is too small (need {} bytes, but got {})",
26729 Self::ENCODED_LEN,
26730 __tmp.remaining(),
26731 )
26732 }
26733 __tmp.put_u64_le(self.usec);
26734 __tmp.put_f32_le(self.x);
26735 __tmp.put_f32_le(self.y);
26736 __tmp.put_f32_le(self.z);
26737 __tmp.put_f32_le(self.roll);
26738 __tmp.put_f32_le(self.pitch);
26739 __tmp.put_f32_le(self.yaw);
26740 for val in &self.covariance {
26741 __tmp.put_f32_le(*val);
26742 }
26743 __tmp.put_u8(self.reset_counter);
26744 if matches!(version, MavlinkVersion::V2) {
26745 let len = __tmp.len();
26746 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26747 } else {
26748 __tmp.len()
26749 }
26750 }
26751}
26752#[doc = "id: 336"]
26753#[doc = "Configure cellular modems. This message is re-emitted as an acknowledgement by the modem. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
26754#[derive(Debug, Clone, PartialEq)]
26755#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26756#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26757pub struct CELLULAR_CONFIG_DATA {
26758 #[doc = "Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
26759 pub enable_lte: u8,
26760 #[doc = "Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
26761 pub enable_pin: u8,
26762 #[doc = "PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response."]
26763 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26764 pub pin: [u8; 16],
26765 #[doc = "New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response."]
26766 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26767 pub new_pin: [u8; 16],
26768 #[doc = "Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response."]
26769 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26770 pub apn: [u8; 32],
26771 #[doc = "Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response."]
26772 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26773 pub puk: [u8; 16],
26774 #[doc = "Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
26775 pub roaming: u8,
26776 #[doc = "Message acceptance response (sent back to GS)."]
26777 pub response: CellularConfigResponse,
26778}
26779impl CELLULAR_CONFIG_DATA {
26780 pub const ENCODED_LEN: usize = 84usize;
26781 pub const DEFAULT: Self = Self {
26782 enable_lte: 0_u8,
26783 enable_pin: 0_u8,
26784 pin: [0_u8; 16usize],
26785 new_pin: [0_u8; 16usize],
26786 apn: [0_u8; 32usize],
26787 puk: [0_u8; 16usize],
26788 roaming: 0_u8,
26789 response: CellularConfigResponse::DEFAULT,
26790 };
26791 #[cfg(feature = "arbitrary")]
26792 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26793 use arbitrary::{Arbitrary, Unstructured};
26794 let mut buf = [0u8; 1024];
26795 rng.fill_bytes(&mut buf);
26796 let mut unstructured = Unstructured::new(&buf);
26797 Self::arbitrary(&mut unstructured).unwrap_or_default()
26798 }
26799}
26800impl Default for CELLULAR_CONFIG_DATA {
26801 fn default() -> Self {
26802 Self::DEFAULT.clone()
26803 }
26804}
26805impl MessageData for CELLULAR_CONFIG_DATA {
26806 type Message = MavMessage;
26807 const ID: u32 = 336u32;
26808 const NAME: &'static str = "CELLULAR_CONFIG";
26809 const EXTRA_CRC: u8 = 245u8;
26810 const ENCODED_LEN: usize = 84usize;
26811 fn deser(
26812 _version: MavlinkVersion,
26813 __input: &[u8],
26814 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26815 let avail_len = __input.len();
26816 let mut payload_buf = [0; Self::ENCODED_LEN];
26817 let mut buf = if avail_len < Self::ENCODED_LEN {
26818 payload_buf[0..avail_len].copy_from_slice(__input);
26819 Bytes::new(&payload_buf)
26820 } else {
26821 Bytes::new(__input)
26822 };
26823 let mut __struct = Self::default();
26824 __struct.enable_lte = buf.get_u8();
26825 __struct.enable_pin = buf.get_u8();
26826 for v in &mut __struct.pin {
26827 let val = buf.get_u8();
26828 *v = val;
26829 }
26830 for v in &mut __struct.new_pin {
26831 let val = buf.get_u8();
26832 *v = val;
26833 }
26834 for v in &mut __struct.apn {
26835 let val = buf.get_u8();
26836 *v = val;
26837 }
26838 for v in &mut __struct.puk {
26839 let val = buf.get_u8();
26840 *v = val;
26841 }
26842 __struct.roaming = buf.get_u8();
26843 let tmp = buf.get_u8();
26844 __struct.response =
26845 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26846 enum_type: "CellularConfigResponse",
26847 value: tmp as u32,
26848 })?;
26849 Ok(__struct)
26850 }
26851 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26852 let mut __tmp = BytesMut::new(bytes);
26853 #[allow(clippy::absurd_extreme_comparisons)]
26854 #[allow(unused_comparisons)]
26855 if __tmp.remaining() < Self::ENCODED_LEN {
26856 panic!(
26857 "buffer is too small (need {} bytes, but got {})",
26858 Self::ENCODED_LEN,
26859 __tmp.remaining(),
26860 )
26861 }
26862 __tmp.put_u8(self.enable_lte);
26863 __tmp.put_u8(self.enable_pin);
26864 for val in &self.pin {
26865 __tmp.put_u8(*val);
26866 }
26867 for val in &self.new_pin {
26868 __tmp.put_u8(*val);
26869 }
26870 for val in &self.apn {
26871 __tmp.put_u8(*val);
26872 }
26873 for val in &self.puk {
26874 __tmp.put_u8(*val);
26875 }
26876 __tmp.put_u8(self.roaming);
26877 __tmp.put_u8(self.response as u8);
26878 if matches!(version, MavlinkVersion::V2) {
26879 let len = __tmp.len();
26880 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26881 } else {
26882 __tmp.len()
26883 }
26884 }
26885}
26886#[doc = "id: 84"]
26887#[doc = "Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system)."]
26888#[derive(Debug, Clone, PartialEq)]
26889#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26890#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26891pub struct SET_POSITION_TARGET_LOCAL_NED_DATA {
26892 #[doc = "Timestamp (time since system boot)."]
26893 pub time_boot_ms: u32,
26894 #[doc = "X Position in NED frame"]
26895 pub x: f32,
26896 #[doc = "Y Position in NED frame"]
26897 pub y: f32,
26898 #[doc = "Z Position in NED frame (note, altitude is negative in NED)"]
26899 pub z: f32,
26900 #[doc = "X velocity in NED frame"]
26901 pub vx: f32,
26902 #[doc = "Y velocity in NED frame"]
26903 pub vy: f32,
26904 #[doc = "Z velocity in NED frame"]
26905 pub vz: f32,
26906 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
26907 pub afx: f32,
26908 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
26909 pub afy: f32,
26910 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
26911 pub afz: f32,
26912 #[doc = "yaw setpoint"]
26913 pub yaw: f32,
26914 #[doc = "yaw rate setpoint"]
26915 pub yaw_rate: f32,
26916 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
26917 pub type_mask: PositionTargetTypemask,
26918 #[doc = "System ID"]
26919 pub target_system: u8,
26920 #[doc = "Component ID"]
26921 pub target_component: u8,
26922 #[doc = "Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9"]
26923 pub coordinate_frame: MavFrame,
26924}
26925impl SET_POSITION_TARGET_LOCAL_NED_DATA {
26926 pub const ENCODED_LEN: usize = 53usize;
26927 pub const DEFAULT: Self = Self {
26928 time_boot_ms: 0_u32,
26929 x: 0.0_f32,
26930 y: 0.0_f32,
26931 z: 0.0_f32,
26932 vx: 0.0_f32,
26933 vy: 0.0_f32,
26934 vz: 0.0_f32,
26935 afx: 0.0_f32,
26936 afy: 0.0_f32,
26937 afz: 0.0_f32,
26938 yaw: 0.0_f32,
26939 yaw_rate: 0.0_f32,
26940 type_mask: PositionTargetTypemask::DEFAULT,
26941 target_system: 0_u8,
26942 target_component: 0_u8,
26943 coordinate_frame: MavFrame::DEFAULT,
26944 };
26945 #[cfg(feature = "arbitrary")]
26946 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26947 use arbitrary::{Arbitrary, Unstructured};
26948 let mut buf = [0u8; 1024];
26949 rng.fill_bytes(&mut buf);
26950 let mut unstructured = Unstructured::new(&buf);
26951 Self::arbitrary(&mut unstructured).unwrap_or_default()
26952 }
26953}
26954impl Default for SET_POSITION_TARGET_LOCAL_NED_DATA {
26955 fn default() -> Self {
26956 Self::DEFAULT.clone()
26957 }
26958}
26959impl MessageData for SET_POSITION_TARGET_LOCAL_NED_DATA {
26960 type Message = MavMessage;
26961 const ID: u32 = 84u32;
26962 const NAME: &'static str = "SET_POSITION_TARGET_LOCAL_NED";
26963 const EXTRA_CRC: u8 = 143u8;
26964 const ENCODED_LEN: usize = 53usize;
26965 fn deser(
26966 _version: MavlinkVersion,
26967 __input: &[u8],
26968 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26969 let avail_len = __input.len();
26970 let mut payload_buf = [0; Self::ENCODED_LEN];
26971 let mut buf = if avail_len < Self::ENCODED_LEN {
26972 payload_buf[0..avail_len].copy_from_slice(__input);
26973 Bytes::new(&payload_buf)
26974 } else {
26975 Bytes::new(__input)
26976 };
26977 let mut __struct = Self::default();
26978 __struct.time_boot_ms = buf.get_u32_le();
26979 __struct.x = buf.get_f32_le();
26980 __struct.y = buf.get_f32_le();
26981 __struct.z = buf.get_f32_le();
26982 __struct.vx = buf.get_f32_le();
26983 __struct.vy = buf.get_f32_le();
26984 __struct.vz = buf.get_f32_le();
26985 __struct.afx = buf.get_f32_le();
26986 __struct.afy = buf.get_f32_le();
26987 __struct.afz = buf.get_f32_le();
26988 __struct.yaw = buf.get_f32_le();
26989 __struct.yaw_rate = buf.get_f32_le();
26990 let tmp = buf.get_u16_le();
26991 __struct.type_mask = PositionTargetTypemask::from_bits(
26992 tmp & PositionTargetTypemask::all().bits(),
26993 )
26994 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
26995 flag_type: "PositionTargetTypemask",
26996 value: tmp as u32,
26997 })?;
26998 __struct.target_system = buf.get_u8();
26999 __struct.target_component = buf.get_u8();
27000 let tmp = buf.get_u8();
27001 __struct.coordinate_frame =
27002 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27003 enum_type: "MavFrame",
27004 value: tmp as u32,
27005 })?;
27006 Ok(__struct)
27007 }
27008 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27009 let mut __tmp = BytesMut::new(bytes);
27010 #[allow(clippy::absurd_extreme_comparisons)]
27011 #[allow(unused_comparisons)]
27012 if __tmp.remaining() < Self::ENCODED_LEN {
27013 panic!(
27014 "buffer is too small (need {} bytes, but got {})",
27015 Self::ENCODED_LEN,
27016 __tmp.remaining(),
27017 )
27018 }
27019 __tmp.put_u32_le(self.time_boot_ms);
27020 __tmp.put_f32_le(self.x);
27021 __tmp.put_f32_le(self.y);
27022 __tmp.put_f32_le(self.z);
27023 __tmp.put_f32_le(self.vx);
27024 __tmp.put_f32_le(self.vy);
27025 __tmp.put_f32_le(self.vz);
27026 __tmp.put_f32_le(self.afx);
27027 __tmp.put_f32_le(self.afy);
27028 __tmp.put_f32_le(self.afz);
27029 __tmp.put_f32_le(self.yaw);
27030 __tmp.put_f32_le(self.yaw_rate);
27031 __tmp.put_u16_le(self.type_mask.bits());
27032 __tmp.put_u8(self.target_system);
27033 __tmp.put_u8(self.target_component);
27034 __tmp.put_u8(self.coordinate_frame as u8);
27035 if matches!(version, MavlinkVersion::V2) {
27036 let len = __tmp.len();
27037 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27038 } else {
27039 __tmp.len()
27040 }
27041 }
27042}
27043#[doc = "id: 49"]
27044#[doc = "Publishes the GPS coordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message."]
27045#[derive(Debug, Clone, PartialEq)]
27046#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27047#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27048pub struct GPS_GLOBAL_ORIGIN_DATA {
27049 #[doc = "Latitude (WGS84)"]
27050 pub latitude: i32,
27051 #[doc = "Longitude (WGS84)"]
27052 pub longitude: i32,
27053 #[doc = "Altitude (MSL). Positive for up."]
27054 pub altitude: i32,
27055 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
27056 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27057 pub time_usec: u64,
27058}
27059impl GPS_GLOBAL_ORIGIN_DATA {
27060 pub const ENCODED_LEN: usize = 20usize;
27061 pub const DEFAULT: Self = Self {
27062 latitude: 0_i32,
27063 longitude: 0_i32,
27064 altitude: 0_i32,
27065 time_usec: 0_u64,
27066 };
27067 #[cfg(feature = "arbitrary")]
27068 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27069 use arbitrary::{Arbitrary, Unstructured};
27070 let mut buf = [0u8; 1024];
27071 rng.fill_bytes(&mut buf);
27072 let mut unstructured = Unstructured::new(&buf);
27073 Self::arbitrary(&mut unstructured).unwrap_or_default()
27074 }
27075}
27076impl Default for GPS_GLOBAL_ORIGIN_DATA {
27077 fn default() -> Self {
27078 Self::DEFAULT.clone()
27079 }
27080}
27081impl MessageData for GPS_GLOBAL_ORIGIN_DATA {
27082 type Message = MavMessage;
27083 const ID: u32 = 49u32;
27084 const NAME: &'static str = "GPS_GLOBAL_ORIGIN";
27085 const EXTRA_CRC: u8 = 39u8;
27086 const ENCODED_LEN: usize = 20usize;
27087 fn deser(
27088 _version: MavlinkVersion,
27089 __input: &[u8],
27090 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27091 let avail_len = __input.len();
27092 let mut payload_buf = [0; Self::ENCODED_LEN];
27093 let mut buf = if avail_len < Self::ENCODED_LEN {
27094 payload_buf[0..avail_len].copy_from_slice(__input);
27095 Bytes::new(&payload_buf)
27096 } else {
27097 Bytes::new(__input)
27098 };
27099 let mut __struct = Self::default();
27100 __struct.latitude = buf.get_i32_le();
27101 __struct.longitude = buf.get_i32_le();
27102 __struct.altitude = buf.get_i32_le();
27103 __struct.time_usec = buf.get_u64_le();
27104 Ok(__struct)
27105 }
27106 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27107 let mut __tmp = BytesMut::new(bytes);
27108 #[allow(clippy::absurd_extreme_comparisons)]
27109 #[allow(unused_comparisons)]
27110 if __tmp.remaining() < Self::ENCODED_LEN {
27111 panic!(
27112 "buffer is too small (need {} bytes, but got {})",
27113 Self::ENCODED_LEN,
27114 __tmp.remaining(),
27115 )
27116 }
27117 __tmp.put_i32_le(self.latitude);
27118 __tmp.put_i32_le(self.longitude);
27119 __tmp.put_i32_le(self.altitude);
27120 __tmp.put_u64_le(self.time_usec);
27121 if matches!(version, MavlinkVersion::V2) {
27122 let len = __tmp.len();
27123 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27124 } else {
27125 __tmp.len()
27126 }
27127 }
27128}
27129#[doc = "id: 34"]
27130#[doc = "The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to INT16_MAX."]
27131#[derive(Debug, Clone, PartialEq)]
27132#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27133#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27134pub struct RC_CHANNELS_SCALED_DATA {
27135 #[doc = "Timestamp (time since system boot)."]
27136 pub time_boot_ms: u32,
27137 #[doc = "RC channel 1 value scaled."]
27138 pub chan1_scaled: i16,
27139 #[doc = "RC channel 2 value scaled."]
27140 pub chan2_scaled: i16,
27141 #[doc = "RC channel 3 value scaled."]
27142 pub chan3_scaled: i16,
27143 #[doc = "RC channel 4 value scaled."]
27144 pub chan4_scaled: i16,
27145 #[doc = "RC channel 5 value scaled."]
27146 pub chan5_scaled: i16,
27147 #[doc = "RC channel 6 value scaled."]
27148 pub chan6_scaled: i16,
27149 #[doc = "RC channel 7 value scaled."]
27150 pub chan7_scaled: i16,
27151 #[doc = "RC channel 8 value scaled."]
27152 pub chan8_scaled: i16,
27153 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
27154 pub port: u8,
27155 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
27156 pub rssi: u8,
27157}
27158impl RC_CHANNELS_SCALED_DATA {
27159 pub const ENCODED_LEN: usize = 22usize;
27160 pub const DEFAULT: Self = Self {
27161 time_boot_ms: 0_u32,
27162 chan1_scaled: 0_i16,
27163 chan2_scaled: 0_i16,
27164 chan3_scaled: 0_i16,
27165 chan4_scaled: 0_i16,
27166 chan5_scaled: 0_i16,
27167 chan6_scaled: 0_i16,
27168 chan7_scaled: 0_i16,
27169 chan8_scaled: 0_i16,
27170 port: 0_u8,
27171 rssi: 0_u8,
27172 };
27173 #[cfg(feature = "arbitrary")]
27174 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27175 use arbitrary::{Arbitrary, Unstructured};
27176 let mut buf = [0u8; 1024];
27177 rng.fill_bytes(&mut buf);
27178 let mut unstructured = Unstructured::new(&buf);
27179 Self::arbitrary(&mut unstructured).unwrap_or_default()
27180 }
27181}
27182impl Default for RC_CHANNELS_SCALED_DATA {
27183 fn default() -> Self {
27184 Self::DEFAULT.clone()
27185 }
27186}
27187impl MessageData for RC_CHANNELS_SCALED_DATA {
27188 type Message = MavMessage;
27189 const ID: u32 = 34u32;
27190 const NAME: &'static str = "RC_CHANNELS_SCALED";
27191 const EXTRA_CRC: u8 = 237u8;
27192 const ENCODED_LEN: usize = 22usize;
27193 fn deser(
27194 _version: MavlinkVersion,
27195 __input: &[u8],
27196 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27197 let avail_len = __input.len();
27198 let mut payload_buf = [0; Self::ENCODED_LEN];
27199 let mut buf = if avail_len < Self::ENCODED_LEN {
27200 payload_buf[0..avail_len].copy_from_slice(__input);
27201 Bytes::new(&payload_buf)
27202 } else {
27203 Bytes::new(__input)
27204 };
27205 let mut __struct = Self::default();
27206 __struct.time_boot_ms = buf.get_u32_le();
27207 __struct.chan1_scaled = buf.get_i16_le();
27208 __struct.chan2_scaled = buf.get_i16_le();
27209 __struct.chan3_scaled = buf.get_i16_le();
27210 __struct.chan4_scaled = buf.get_i16_le();
27211 __struct.chan5_scaled = buf.get_i16_le();
27212 __struct.chan6_scaled = buf.get_i16_le();
27213 __struct.chan7_scaled = buf.get_i16_le();
27214 __struct.chan8_scaled = buf.get_i16_le();
27215 __struct.port = buf.get_u8();
27216 __struct.rssi = buf.get_u8();
27217 Ok(__struct)
27218 }
27219 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27220 let mut __tmp = BytesMut::new(bytes);
27221 #[allow(clippy::absurd_extreme_comparisons)]
27222 #[allow(unused_comparisons)]
27223 if __tmp.remaining() < Self::ENCODED_LEN {
27224 panic!(
27225 "buffer is too small (need {} bytes, but got {})",
27226 Self::ENCODED_LEN,
27227 __tmp.remaining(),
27228 )
27229 }
27230 __tmp.put_u32_le(self.time_boot_ms);
27231 __tmp.put_i16_le(self.chan1_scaled);
27232 __tmp.put_i16_le(self.chan2_scaled);
27233 __tmp.put_i16_le(self.chan3_scaled);
27234 __tmp.put_i16_le(self.chan4_scaled);
27235 __tmp.put_i16_le(self.chan5_scaled);
27236 __tmp.put_i16_le(self.chan6_scaled);
27237 __tmp.put_i16_le(self.chan7_scaled);
27238 __tmp.put_i16_le(self.chan8_scaled);
27239 __tmp.put_u8(self.port);
27240 __tmp.put_u8(self.rssi);
27241 if matches!(version, MavlinkVersion::V2) {
27242 let len = __tmp.len();
27243 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27244 } else {
27245 __tmp.len()
27246 }
27247 }
27248}
27249#[doc = "id: 30"]
27250#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, Y-right, X-front, ZYX, intrinsic)."]
27251#[derive(Debug, Clone, PartialEq)]
27252#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27253#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27254pub struct ATTITUDE_DATA {
27255 #[doc = "Timestamp (time since system boot)."]
27256 pub time_boot_ms: u32,
27257 #[doc = "Roll angle (-pi..+pi)"]
27258 pub roll: f32,
27259 #[doc = "Pitch angle (-pi..+pi)"]
27260 pub pitch: f32,
27261 #[doc = "Yaw angle (-pi..+pi)"]
27262 pub yaw: f32,
27263 #[doc = "Roll angular speed"]
27264 pub rollspeed: f32,
27265 #[doc = "Pitch angular speed"]
27266 pub pitchspeed: f32,
27267 #[doc = "Yaw angular speed"]
27268 pub yawspeed: f32,
27269}
27270impl ATTITUDE_DATA {
27271 pub const ENCODED_LEN: usize = 28usize;
27272 pub const DEFAULT: Self = Self {
27273 time_boot_ms: 0_u32,
27274 roll: 0.0_f32,
27275 pitch: 0.0_f32,
27276 yaw: 0.0_f32,
27277 rollspeed: 0.0_f32,
27278 pitchspeed: 0.0_f32,
27279 yawspeed: 0.0_f32,
27280 };
27281 #[cfg(feature = "arbitrary")]
27282 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27283 use arbitrary::{Arbitrary, Unstructured};
27284 let mut buf = [0u8; 1024];
27285 rng.fill_bytes(&mut buf);
27286 let mut unstructured = Unstructured::new(&buf);
27287 Self::arbitrary(&mut unstructured).unwrap_or_default()
27288 }
27289}
27290impl Default for ATTITUDE_DATA {
27291 fn default() -> Self {
27292 Self::DEFAULT.clone()
27293 }
27294}
27295impl MessageData for ATTITUDE_DATA {
27296 type Message = MavMessage;
27297 const ID: u32 = 30u32;
27298 const NAME: &'static str = "ATTITUDE";
27299 const EXTRA_CRC: u8 = 39u8;
27300 const ENCODED_LEN: usize = 28usize;
27301 fn deser(
27302 _version: MavlinkVersion,
27303 __input: &[u8],
27304 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27305 let avail_len = __input.len();
27306 let mut payload_buf = [0; Self::ENCODED_LEN];
27307 let mut buf = if avail_len < Self::ENCODED_LEN {
27308 payload_buf[0..avail_len].copy_from_slice(__input);
27309 Bytes::new(&payload_buf)
27310 } else {
27311 Bytes::new(__input)
27312 };
27313 let mut __struct = Self::default();
27314 __struct.time_boot_ms = buf.get_u32_le();
27315 __struct.roll = buf.get_f32_le();
27316 __struct.pitch = buf.get_f32_le();
27317 __struct.yaw = buf.get_f32_le();
27318 __struct.rollspeed = buf.get_f32_le();
27319 __struct.pitchspeed = buf.get_f32_le();
27320 __struct.yawspeed = buf.get_f32_le();
27321 Ok(__struct)
27322 }
27323 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27324 let mut __tmp = BytesMut::new(bytes);
27325 #[allow(clippy::absurd_extreme_comparisons)]
27326 #[allow(unused_comparisons)]
27327 if __tmp.remaining() < Self::ENCODED_LEN {
27328 panic!(
27329 "buffer is too small (need {} bytes, but got {})",
27330 Self::ENCODED_LEN,
27331 __tmp.remaining(),
27332 )
27333 }
27334 __tmp.put_u32_le(self.time_boot_ms);
27335 __tmp.put_f32_le(self.roll);
27336 __tmp.put_f32_le(self.pitch);
27337 __tmp.put_f32_le(self.yaw);
27338 __tmp.put_f32_le(self.rollspeed);
27339 __tmp.put_f32_le(self.pitchspeed);
27340 __tmp.put_f32_le(self.yawspeed);
27341 if matches!(version, MavlinkVersion::V2) {
27342 let len = __tmp.len();
27343 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27344 } else {
27345 __tmp.len()
27346 }
27347 }
27348}
27349#[doc = "id: 25"]
27350#[doc = "The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION_INT for the global position estimate. This message can contain information for up to 20 satellites."]
27351#[derive(Debug, Clone, PartialEq)]
27352#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27353#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27354pub struct GPS_STATUS_DATA {
27355 #[doc = "Number of satellites visible"]
27356 pub satellites_visible: u8,
27357 #[doc = "Global satellite ID"]
27358 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27359 pub satellite_prn: [u8; 20],
27360 #[doc = "0: Satellite not used, 1: used for localization"]
27361 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27362 pub satellite_used: [u8; 20],
27363 #[doc = "Elevation (0: right on top of receiver, 90: on the horizon) of satellite"]
27364 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27365 pub satellite_elevation: [u8; 20],
27366 #[doc = "Direction of satellite, 0: 0 deg, 255: 360 deg."]
27367 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27368 pub satellite_azimuth: [u8; 20],
27369 #[doc = "Signal to noise ratio of satellite"]
27370 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27371 pub satellite_snr: [u8; 20],
27372}
27373impl GPS_STATUS_DATA {
27374 pub const ENCODED_LEN: usize = 101usize;
27375 pub const DEFAULT: Self = Self {
27376 satellites_visible: 0_u8,
27377 satellite_prn: [0_u8; 20usize],
27378 satellite_used: [0_u8; 20usize],
27379 satellite_elevation: [0_u8; 20usize],
27380 satellite_azimuth: [0_u8; 20usize],
27381 satellite_snr: [0_u8; 20usize],
27382 };
27383 #[cfg(feature = "arbitrary")]
27384 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27385 use arbitrary::{Arbitrary, Unstructured};
27386 let mut buf = [0u8; 1024];
27387 rng.fill_bytes(&mut buf);
27388 let mut unstructured = Unstructured::new(&buf);
27389 Self::arbitrary(&mut unstructured).unwrap_or_default()
27390 }
27391}
27392impl Default for GPS_STATUS_DATA {
27393 fn default() -> Self {
27394 Self::DEFAULT.clone()
27395 }
27396}
27397impl MessageData for GPS_STATUS_DATA {
27398 type Message = MavMessage;
27399 const ID: u32 = 25u32;
27400 const NAME: &'static str = "GPS_STATUS";
27401 const EXTRA_CRC: u8 = 23u8;
27402 const ENCODED_LEN: usize = 101usize;
27403 fn deser(
27404 _version: MavlinkVersion,
27405 __input: &[u8],
27406 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27407 let avail_len = __input.len();
27408 let mut payload_buf = [0; Self::ENCODED_LEN];
27409 let mut buf = if avail_len < Self::ENCODED_LEN {
27410 payload_buf[0..avail_len].copy_from_slice(__input);
27411 Bytes::new(&payload_buf)
27412 } else {
27413 Bytes::new(__input)
27414 };
27415 let mut __struct = Self::default();
27416 __struct.satellites_visible = buf.get_u8();
27417 for v in &mut __struct.satellite_prn {
27418 let val = buf.get_u8();
27419 *v = val;
27420 }
27421 for v in &mut __struct.satellite_used {
27422 let val = buf.get_u8();
27423 *v = val;
27424 }
27425 for v in &mut __struct.satellite_elevation {
27426 let val = buf.get_u8();
27427 *v = val;
27428 }
27429 for v in &mut __struct.satellite_azimuth {
27430 let val = buf.get_u8();
27431 *v = val;
27432 }
27433 for v in &mut __struct.satellite_snr {
27434 let val = buf.get_u8();
27435 *v = val;
27436 }
27437 Ok(__struct)
27438 }
27439 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27440 let mut __tmp = BytesMut::new(bytes);
27441 #[allow(clippy::absurd_extreme_comparisons)]
27442 #[allow(unused_comparisons)]
27443 if __tmp.remaining() < Self::ENCODED_LEN {
27444 panic!(
27445 "buffer is too small (need {} bytes, but got {})",
27446 Self::ENCODED_LEN,
27447 __tmp.remaining(),
27448 )
27449 }
27450 __tmp.put_u8(self.satellites_visible);
27451 for val in &self.satellite_prn {
27452 __tmp.put_u8(*val);
27453 }
27454 for val in &self.satellite_used {
27455 __tmp.put_u8(*val);
27456 }
27457 for val in &self.satellite_elevation {
27458 __tmp.put_u8(*val);
27459 }
27460 for val in &self.satellite_azimuth {
27461 __tmp.put_u8(*val);
27462 }
27463 for val in &self.satellite_snr {
27464 __tmp.put_u8(*val);
27465 }
27466 if matches!(version, MavlinkVersion::V2) {
27467 let len = __tmp.len();
27468 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27469 } else {
27470 __tmp.len()
27471 }
27472 }
27473}
27474#[doc = "id: 146"]
27475#[doc = "The smoothed, monotonic system state used to feed the control loops of the system."]
27476#[derive(Debug, Clone, PartialEq)]
27477#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27478#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27479pub struct CONTROL_SYSTEM_STATE_DATA {
27480 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
27481 pub time_usec: u64,
27482 #[doc = "X acceleration in body frame"]
27483 pub x_acc: f32,
27484 #[doc = "Y acceleration in body frame"]
27485 pub y_acc: f32,
27486 #[doc = "Z acceleration in body frame"]
27487 pub z_acc: f32,
27488 #[doc = "X velocity in body frame"]
27489 pub x_vel: f32,
27490 #[doc = "Y velocity in body frame"]
27491 pub y_vel: f32,
27492 #[doc = "Z velocity in body frame"]
27493 pub z_vel: f32,
27494 #[doc = "X position in local frame"]
27495 pub x_pos: f32,
27496 #[doc = "Y position in local frame"]
27497 pub y_pos: f32,
27498 #[doc = "Z position in local frame"]
27499 pub z_pos: f32,
27500 #[doc = "Airspeed, set to -1 if unknown"]
27501 pub airspeed: f32,
27502 #[doc = "Variance of body velocity estimate"]
27503 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27504 pub vel_variance: [f32; 3],
27505 #[doc = "Variance in local position"]
27506 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27507 pub pos_variance: [f32; 3],
27508 #[doc = "The attitude, represented as Quaternion"]
27509 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27510 pub q: [f32; 4],
27511 #[doc = "Angular rate in roll axis"]
27512 pub roll_rate: f32,
27513 #[doc = "Angular rate in pitch axis"]
27514 pub pitch_rate: f32,
27515 #[doc = "Angular rate in yaw axis"]
27516 pub yaw_rate: f32,
27517}
27518impl CONTROL_SYSTEM_STATE_DATA {
27519 pub const ENCODED_LEN: usize = 100usize;
27520 pub const DEFAULT: Self = Self {
27521 time_usec: 0_u64,
27522 x_acc: 0.0_f32,
27523 y_acc: 0.0_f32,
27524 z_acc: 0.0_f32,
27525 x_vel: 0.0_f32,
27526 y_vel: 0.0_f32,
27527 z_vel: 0.0_f32,
27528 x_pos: 0.0_f32,
27529 y_pos: 0.0_f32,
27530 z_pos: 0.0_f32,
27531 airspeed: 0.0_f32,
27532 vel_variance: [0.0_f32; 3usize],
27533 pos_variance: [0.0_f32; 3usize],
27534 q: [0.0_f32; 4usize],
27535 roll_rate: 0.0_f32,
27536 pitch_rate: 0.0_f32,
27537 yaw_rate: 0.0_f32,
27538 };
27539 #[cfg(feature = "arbitrary")]
27540 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27541 use arbitrary::{Arbitrary, Unstructured};
27542 let mut buf = [0u8; 1024];
27543 rng.fill_bytes(&mut buf);
27544 let mut unstructured = Unstructured::new(&buf);
27545 Self::arbitrary(&mut unstructured).unwrap_or_default()
27546 }
27547}
27548impl Default for CONTROL_SYSTEM_STATE_DATA {
27549 fn default() -> Self {
27550 Self::DEFAULT.clone()
27551 }
27552}
27553impl MessageData for CONTROL_SYSTEM_STATE_DATA {
27554 type Message = MavMessage;
27555 const ID: u32 = 146u32;
27556 const NAME: &'static str = "CONTROL_SYSTEM_STATE";
27557 const EXTRA_CRC: u8 = 103u8;
27558 const ENCODED_LEN: usize = 100usize;
27559 fn deser(
27560 _version: MavlinkVersion,
27561 __input: &[u8],
27562 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27563 let avail_len = __input.len();
27564 let mut payload_buf = [0; Self::ENCODED_LEN];
27565 let mut buf = if avail_len < Self::ENCODED_LEN {
27566 payload_buf[0..avail_len].copy_from_slice(__input);
27567 Bytes::new(&payload_buf)
27568 } else {
27569 Bytes::new(__input)
27570 };
27571 let mut __struct = Self::default();
27572 __struct.time_usec = buf.get_u64_le();
27573 __struct.x_acc = buf.get_f32_le();
27574 __struct.y_acc = buf.get_f32_le();
27575 __struct.z_acc = buf.get_f32_le();
27576 __struct.x_vel = buf.get_f32_le();
27577 __struct.y_vel = buf.get_f32_le();
27578 __struct.z_vel = buf.get_f32_le();
27579 __struct.x_pos = buf.get_f32_le();
27580 __struct.y_pos = buf.get_f32_le();
27581 __struct.z_pos = buf.get_f32_le();
27582 __struct.airspeed = buf.get_f32_le();
27583 for v in &mut __struct.vel_variance {
27584 let val = buf.get_f32_le();
27585 *v = val;
27586 }
27587 for v in &mut __struct.pos_variance {
27588 let val = buf.get_f32_le();
27589 *v = val;
27590 }
27591 for v in &mut __struct.q {
27592 let val = buf.get_f32_le();
27593 *v = val;
27594 }
27595 __struct.roll_rate = buf.get_f32_le();
27596 __struct.pitch_rate = buf.get_f32_le();
27597 __struct.yaw_rate = buf.get_f32_le();
27598 Ok(__struct)
27599 }
27600 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27601 let mut __tmp = BytesMut::new(bytes);
27602 #[allow(clippy::absurd_extreme_comparisons)]
27603 #[allow(unused_comparisons)]
27604 if __tmp.remaining() < Self::ENCODED_LEN {
27605 panic!(
27606 "buffer is too small (need {} bytes, but got {})",
27607 Self::ENCODED_LEN,
27608 __tmp.remaining(),
27609 )
27610 }
27611 __tmp.put_u64_le(self.time_usec);
27612 __tmp.put_f32_le(self.x_acc);
27613 __tmp.put_f32_le(self.y_acc);
27614 __tmp.put_f32_le(self.z_acc);
27615 __tmp.put_f32_le(self.x_vel);
27616 __tmp.put_f32_le(self.y_vel);
27617 __tmp.put_f32_le(self.z_vel);
27618 __tmp.put_f32_le(self.x_pos);
27619 __tmp.put_f32_le(self.y_pos);
27620 __tmp.put_f32_le(self.z_pos);
27621 __tmp.put_f32_le(self.airspeed);
27622 for val in &self.vel_variance {
27623 __tmp.put_f32_le(*val);
27624 }
27625 for val in &self.pos_variance {
27626 __tmp.put_f32_le(*val);
27627 }
27628 for val in &self.q {
27629 __tmp.put_f32_le(*val);
27630 }
27631 __tmp.put_f32_le(self.roll_rate);
27632 __tmp.put_f32_le(self.pitch_rate);
27633 __tmp.put_f32_le(self.yaw_rate);
27634 if matches!(version, MavlinkVersion::V2) {
27635 let len = __tmp.len();
27636 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27637 } else {
27638 __tmp.len()
27639 }
27640 }
27641}
27642#[doc = "id: 321"]
27643#[doc = "Request all parameters of this component. All parameters should be emitted in response as PARAM_EXT_VALUE."]
27644#[derive(Debug, Clone, PartialEq)]
27645#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27646#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27647pub struct PARAM_EXT_REQUEST_LIST_DATA {
27648 #[doc = "System ID"]
27649 pub target_system: u8,
27650 #[doc = "Component ID"]
27651 pub target_component: u8,
27652}
27653impl PARAM_EXT_REQUEST_LIST_DATA {
27654 pub const ENCODED_LEN: usize = 2usize;
27655 pub const DEFAULT: Self = Self {
27656 target_system: 0_u8,
27657 target_component: 0_u8,
27658 };
27659 #[cfg(feature = "arbitrary")]
27660 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27661 use arbitrary::{Arbitrary, Unstructured};
27662 let mut buf = [0u8; 1024];
27663 rng.fill_bytes(&mut buf);
27664 let mut unstructured = Unstructured::new(&buf);
27665 Self::arbitrary(&mut unstructured).unwrap_or_default()
27666 }
27667}
27668impl Default for PARAM_EXT_REQUEST_LIST_DATA {
27669 fn default() -> Self {
27670 Self::DEFAULT.clone()
27671 }
27672}
27673impl MessageData for PARAM_EXT_REQUEST_LIST_DATA {
27674 type Message = MavMessage;
27675 const ID: u32 = 321u32;
27676 const NAME: &'static str = "PARAM_EXT_REQUEST_LIST";
27677 const EXTRA_CRC: u8 = 88u8;
27678 const ENCODED_LEN: usize = 2usize;
27679 fn deser(
27680 _version: MavlinkVersion,
27681 __input: &[u8],
27682 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27683 let avail_len = __input.len();
27684 let mut payload_buf = [0; Self::ENCODED_LEN];
27685 let mut buf = if avail_len < Self::ENCODED_LEN {
27686 payload_buf[0..avail_len].copy_from_slice(__input);
27687 Bytes::new(&payload_buf)
27688 } else {
27689 Bytes::new(__input)
27690 };
27691 let mut __struct = Self::default();
27692 __struct.target_system = buf.get_u8();
27693 __struct.target_component = buf.get_u8();
27694 Ok(__struct)
27695 }
27696 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27697 let mut __tmp = BytesMut::new(bytes);
27698 #[allow(clippy::absurd_extreme_comparisons)]
27699 #[allow(unused_comparisons)]
27700 if __tmp.remaining() < Self::ENCODED_LEN {
27701 panic!(
27702 "buffer is too small (need {} bytes, but got {})",
27703 Self::ENCODED_LEN,
27704 __tmp.remaining(),
27705 )
27706 }
27707 __tmp.put_u8(self.target_system);
27708 __tmp.put_u8(self.target_component);
27709 if matches!(version, MavlinkVersion::V2) {
27710 let len = __tmp.len();
27711 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27712 } else {
27713 __tmp.len()
27714 }
27715 }
27716}
27717#[doc = "id: 269"]
27718#[doc = "Information about video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE, where param2 indicates the video stream id: 0 for all streams, 1 for first, 2 for second, etc."]
27719#[derive(Debug, Clone, PartialEq)]
27720#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27721#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27722pub struct VIDEO_STREAM_INFORMATION_DATA {
27723 #[doc = "Frame rate."]
27724 pub framerate: f32,
27725 #[doc = "Bit rate."]
27726 pub bitrate: u32,
27727 #[doc = "Bitmap of stream status flags."]
27728 pub flags: VideoStreamStatusFlags,
27729 #[doc = "Horizontal resolution."]
27730 pub resolution_h: u16,
27731 #[doc = "Vertical resolution."]
27732 pub resolution_v: u16,
27733 #[doc = "Video image rotation clockwise."]
27734 pub rotation: u16,
27735 #[doc = "Horizontal Field of view."]
27736 pub hfov: u16,
27737 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
27738 pub stream_id: u8,
27739 #[doc = "Number of streams available."]
27740 pub count: u8,
27741 #[doc = "Type of stream."]
27742 pub mavtype: VideoStreamType,
27743 #[doc = "Stream name."]
27744 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27745 pub name: [u8; 32],
27746 #[doc = "Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to)."]
27747 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27748 pub uri: [u8; 160],
27749 #[doc = "Encoding of stream."]
27750 #[cfg_attr(feature = "serde", serde(default))]
27751 pub encoding: VideoStreamEncoding,
27752 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
27753 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27754 pub camera_device_id: u8,
27755}
27756impl VIDEO_STREAM_INFORMATION_DATA {
27757 pub const ENCODED_LEN: usize = 215usize;
27758 pub const DEFAULT: Self = Self {
27759 framerate: 0.0_f32,
27760 bitrate: 0_u32,
27761 flags: VideoStreamStatusFlags::DEFAULT,
27762 resolution_h: 0_u16,
27763 resolution_v: 0_u16,
27764 rotation: 0_u16,
27765 hfov: 0_u16,
27766 stream_id: 0_u8,
27767 count: 0_u8,
27768 mavtype: VideoStreamType::DEFAULT,
27769 name: [0_u8; 32usize],
27770 uri: [0_u8; 160usize],
27771 encoding: VideoStreamEncoding::DEFAULT,
27772 camera_device_id: 0_u8,
27773 };
27774 #[cfg(feature = "arbitrary")]
27775 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27776 use arbitrary::{Arbitrary, Unstructured};
27777 let mut buf = [0u8; 1024];
27778 rng.fill_bytes(&mut buf);
27779 let mut unstructured = Unstructured::new(&buf);
27780 Self::arbitrary(&mut unstructured).unwrap_or_default()
27781 }
27782}
27783impl Default for VIDEO_STREAM_INFORMATION_DATA {
27784 fn default() -> Self {
27785 Self::DEFAULT.clone()
27786 }
27787}
27788impl MessageData for VIDEO_STREAM_INFORMATION_DATA {
27789 type Message = MavMessage;
27790 const ID: u32 = 269u32;
27791 const NAME: &'static str = "VIDEO_STREAM_INFORMATION";
27792 const EXTRA_CRC: u8 = 109u8;
27793 const ENCODED_LEN: usize = 215usize;
27794 fn deser(
27795 _version: MavlinkVersion,
27796 __input: &[u8],
27797 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27798 let avail_len = __input.len();
27799 let mut payload_buf = [0; Self::ENCODED_LEN];
27800 let mut buf = if avail_len < Self::ENCODED_LEN {
27801 payload_buf[0..avail_len].copy_from_slice(__input);
27802 Bytes::new(&payload_buf)
27803 } else {
27804 Bytes::new(__input)
27805 };
27806 let mut __struct = Self::default();
27807 __struct.framerate = buf.get_f32_le();
27808 __struct.bitrate = buf.get_u32_le();
27809 let tmp = buf.get_u16_le();
27810 __struct.flags = VideoStreamStatusFlags::from_bits(
27811 tmp & VideoStreamStatusFlags::all().bits(),
27812 )
27813 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
27814 flag_type: "VideoStreamStatusFlags",
27815 value: tmp as u32,
27816 })?;
27817 __struct.resolution_h = buf.get_u16_le();
27818 __struct.resolution_v = buf.get_u16_le();
27819 __struct.rotation = buf.get_u16_le();
27820 __struct.hfov = buf.get_u16_le();
27821 __struct.stream_id = buf.get_u8();
27822 __struct.count = buf.get_u8();
27823 let tmp = buf.get_u8();
27824 __struct.mavtype =
27825 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27826 enum_type: "VideoStreamType",
27827 value: tmp as u32,
27828 })?;
27829 for v in &mut __struct.name {
27830 let val = buf.get_u8();
27831 *v = val;
27832 }
27833 for v in &mut __struct.uri {
27834 let val = buf.get_u8();
27835 *v = val;
27836 }
27837 let tmp = buf.get_u8();
27838 __struct.encoding =
27839 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27840 enum_type: "VideoStreamEncoding",
27841 value: tmp as u32,
27842 })?;
27843 __struct.camera_device_id = buf.get_u8();
27844 Ok(__struct)
27845 }
27846 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27847 let mut __tmp = BytesMut::new(bytes);
27848 #[allow(clippy::absurd_extreme_comparisons)]
27849 #[allow(unused_comparisons)]
27850 if __tmp.remaining() < Self::ENCODED_LEN {
27851 panic!(
27852 "buffer is too small (need {} bytes, but got {})",
27853 Self::ENCODED_LEN,
27854 __tmp.remaining(),
27855 )
27856 }
27857 __tmp.put_f32_le(self.framerate);
27858 __tmp.put_u32_le(self.bitrate);
27859 __tmp.put_u16_le(self.flags.bits());
27860 __tmp.put_u16_le(self.resolution_h);
27861 __tmp.put_u16_le(self.resolution_v);
27862 __tmp.put_u16_le(self.rotation);
27863 __tmp.put_u16_le(self.hfov);
27864 __tmp.put_u8(self.stream_id);
27865 __tmp.put_u8(self.count);
27866 __tmp.put_u8(self.mavtype as u8);
27867 for val in &self.name {
27868 __tmp.put_u8(*val);
27869 }
27870 for val in &self.uri {
27871 __tmp.put_u8(*val);
27872 }
27873 __tmp.put_u8(self.encoding as u8);
27874 __tmp.put_u8(self.camera_device_id);
27875 if matches!(version, MavlinkVersion::V2) {
27876 let len = __tmp.len();
27877 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27878 } else {
27879 __tmp.len()
27880 }
27881 }
27882}
27883#[doc = "id: 142"]
27884#[doc = "The autopilot is requesting a resource (file, binary, other type of data)."]
27885#[derive(Debug, Clone, PartialEq)]
27886#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27887#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27888pub struct RESOURCE_REQUEST_DATA {
27889 #[doc = "Request ID. This ID should be re-used when sending back URI contents"]
27890 pub request_id: u8,
27891 #[doc = "The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary"]
27892 pub uri_type: u8,
27893 #[doc = "The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)"]
27894 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27895 pub uri: [u8; 120],
27896 #[doc = "The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream."]
27897 pub transfer_type: u8,
27898 #[doc = "The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP)."]
27899 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27900 pub storage: [u8; 120],
27901}
27902impl RESOURCE_REQUEST_DATA {
27903 pub const ENCODED_LEN: usize = 243usize;
27904 pub const DEFAULT: Self = Self {
27905 request_id: 0_u8,
27906 uri_type: 0_u8,
27907 uri: [0_u8; 120usize],
27908 transfer_type: 0_u8,
27909 storage: [0_u8; 120usize],
27910 };
27911 #[cfg(feature = "arbitrary")]
27912 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27913 use arbitrary::{Arbitrary, Unstructured};
27914 let mut buf = [0u8; 1024];
27915 rng.fill_bytes(&mut buf);
27916 let mut unstructured = Unstructured::new(&buf);
27917 Self::arbitrary(&mut unstructured).unwrap_or_default()
27918 }
27919}
27920impl Default for RESOURCE_REQUEST_DATA {
27921 fn default() -> Self {
27922 Self::DEFAULT.clone()
27923 }
27924}
27925impl MessageData for RESOURCE_REQUEST_DATA {
27926 type Message = MavMessage;
27927 const ID: u32 = 142u32;
27928 const NAME: &'static str = "RESOURCE_REQUEST";
27929 const EXTRA_CRC: u8 = 72u8;
27930 const ENCODED_LEN: usize = 243usize;
27931 fn deser(
27932 _version: MavlinkVersion,
27933 __input: &[u8],
27934 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27935 let avail_len = __input.len();
27936 let mut payload_buf = [0; Self::ENCODED_LEN];
27937 let mut buf = if avail_len < Self::ENCODED_LEN {
27938 payload_buf[0..avail_len].copy_from_slice(__input);
27939 Bytes::new(&payload_buf)
27940 } else {
27941 Bytes::new(__input)
27942 };
27943 let mut __struct = Self::default();
27944 __struct.request_id = buf.get_u8();
27945 __struct.uri_type = buf.get_u8();
27946 for v in &mut __struct.uri {
27947 let val = buf.get_u8();
27948 *v = val;
27949 }
27950 __struct.transfer_type = buf.get_u8();
27951 for v in &mut __struct.storage {
27952 let val = buf.get_u8();
27953 *v = val;
27954 }
27955 Ok(__struct)
27956 }
27957 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27958 let mut __tmp = BytesMut::new(bytes);
27959 #[allow(clippy::absurd_extreme_comparisons)]
27960 #[allow(unused_comparisons)]
27961 if __tmp.remaining() < Self::ENCODED_LEN {
27962 panic!(
27963 "buffer is too small (need {} bytes, but got {})",
27964 Self::ENCODED_LEN,
27965 __tmp.remaining(),
27966 )
27967 }
27968 __tmp.put_u8(self.request_id);
27969 __tmp.put_u8(self.uri_type);
27970 for val in &self.uri {
27971 __tmp.put_u8(*val);
27972 }
27973 __tmp.put_u8(self.transfer_type);
27974 for val in &self.storage {
27975 __tmp.put_u8(*val);
27976 }
27977 if matches!(version, MavlinkVersion::V2) {
27978 let len = __tmp.len();
27979 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27980 } else {
27981 __tmp.len()
27982 }
27983 }
27984}
27985#[doc = "id: 105"]
27986#[doc = "The IMU readings in SI units in NED body frame."]
27987#[derive(Debug, Clone, PartialEq)]
27988#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27989#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27990pub struct HIGHRES_IMU_DATA {
27991 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
27992 pub time_usec: u64,
27993 #[doc = "X acceleration"]
27994 pub xacc: f32,
27995 #[doc = "Y acceleration"]
27996 pub yacc: f32,
27997 #[doc = "Z acceleration"]
27998 pub zacc: f32,
27999 #[doc = "Angular speed around X axis"]
28000 pub xgyro: f32,
28001 #[doc = "Angular speed around Y axis"]
28002 pub ygyro: f32,
28003 #[doc = "Angular speed around Z axis"]
28004 pub zgyro: f32,
28005 #[doc = "X Magnetic field"]
28006 pub xmag: f32,
28007 #[doc = "Y Magnetic field"]
28008 pub ymag: f32,
28009 #[doc = "Z Magnetic field"]
28010 pub zmag: f32,
28011 #[doc = "Absolute pressure"]
28012 pub abs_pressure: f32,
28013 #[doc = "Differential pressure"]
28014 pub diff_pressure: f32,
28015 #[doc = "Altitude calculated from pressure"]
28016 pub pressure_alt: f32,
28017 #[doc = "Temperature"]
28018 pub temperature: f32,
28019 #[doc = "Bitmap for fields that have updated since last message"]
28020 pub fields_updated: HighresImuUpdatedFlags,
28021 #[doc = "Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)"]
28022 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28023 pub id: u8,
28024}
28025impl HIGHRES_IMU_DATA {
28026 pub const ENCODED_LEN: usize = 63usize;
28027 pub const DEFAULT: Self = Self {
28028 time_usec: 0_u64,
28029 xacc: 0.0_f32,
28030 yacc: 0.0_f32,
28031 zacc: 0.0_f32,
28032 xgyro: 0.0_f32,
28033 ygyro: 0.0_f32,
28034 zgyro: 0.0_f32,
28035 xmag: 0.0_f32,
28036 ymag: 0.0_f32,
28037 zmag: 0.0_f32,
28038 abs_pressure: 0.0_f32,
28039 diff_pressure: 0.0_f32,
28040 pressure_alt: 0.0_f32,
28041 temperature: 0.0_f32,
28042 fields_updated: HighresImuUpdatedFlags::DEFAULT,
28043 id: 0_u8,
28044 };
28045 #[cfg(feature = "arbitrary")]
28046 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28047 use arbitrary::{Arbitrary, Unstructured};
28048 let mut buf = [0u8; 1024];
28049 rng.fill_bytes(&mut buf);
28050 let mut unstructured = Unstructured::new(&buf);
28051 Self::arbitrary(&mut unstructured).unwrap_or_default()
28052 }
28053}
28054impl Default for HIGHRES_IMU_DATA {
28055 fn default() -> Self {
28056 Self::DEFAULT.clone()
28057 }
28058}
28059impl MessageData for HIGHRES_IMU_DATA {
28060 type Message = MavMessage;
28061 const ID: u32 = 105u32;
28062 const NAME: &'static str = "HIGHRES_IMU";
28063 const EXTRA_CRC: u8 = 93u8;
28064 const ENCODED_LEN: usize = 63usize;
28065 fn deser(
28066 _version: MavlinkVersion,
28067 __input: &[u8],
28068 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28069 let avail_len = __input.len();
28070 let mut payload_buf = [0; Self::ENCODED_LEN];
28071 let mut buf = if avail_len < Self::ENCODED_LEN {
28072 payload_buf[0..avail_len].copy_from_slice(__input);
28073 Bytes::new(&payload_buf)
28074 } else {
28075 Bytes::new(__input)
28076 };
28077 let mut __struct = Self::default();
28078 __struct.time_usec = buf.get_u64_le();
28079 __struct.xacc = buf.get_f32_le();
28080 __struct.yacc = buf.get_f32_le();
28081 __struct.zacc = buf.get_f32_le();
28082 __struct.xgyro = buf.get_f32_le();
28083 __struct.ygyro = buf.get_f32_le();
28084 __struct.zgyro = buf.get_f32_le();
28085 __struct.xmag = buf.get_f32_le();
28086 __struct.ymag = buf.get_f32_le();
28087 __struct.zmag = buf.get_f32_le();
28088 __struct.abs_pressure = buf.get_f32_le();
28089 __struct.diff_pressure = buf.get_f32_le();
28090 __struct.pressure_alt = buf.get_f32_le();
28091 __struct.temperature = buf.get_f32_le();
28092 let tmp = buf.get_u16_le();
28093 __struct.fields_updated = HighresImuUpdatedFlags::from_bits(
28094 tmp & HighresImuUpdatedFlags::all().bits(),
28095 )
28096 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28097 flag_type: "HighresImuUpdatedFlags",
28098 value: tmp as u32,
28099 })?;
28100 __struct.id = buf.get_u8();
28101 Ok(__struct)
28102 }
28103 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28104 let mut __tmp = BytesMut::new(bytes);
28105 #[allow(clippy::absurd_extreme_comparisons)]
28106 #[allow(unused_comparisons)]
28107 if __tmp.remaining() < Self::ENCODED_LEN {
28108 panic!(
28109 "buffer is too small (need {} bytes, but got {})",
28110 Self::ENCODED_LEN,
28111 __tmp.remaining(),
28112 )
28113 }
28114 __tmp.put_u64_le(self.time_usec);
28115 __tmp.put_f32_le(self.xacc);
28116 __tmp.put_f32_le(self.yacc);
28117 __tmp.put_f32_le(self.zacc);
28118 __tmp.put_f32_le(self.xgyro);
28119 __tmp.put_f32_le(self.ygyro);
28120 __tmp.put_f32_le(self.zgyro);
28121 __tmp.put_f32_le(self.xmag);
28122 __tmp.put_f32_le(self.ymag);
28123 __tmp.put_f32_le(self.zmag);
28124 __tmp.put_f32_le(self.abs_pressure);
28125 __tmp.put_f32_le(self.diff_pressure);
28126 __tmp.put_f32_le(self.pressure_alt);
28127 __tmp.put_f32_le(self.temperature);
28128 __tmp.put_u16_le(self.fields_updated.bits());
28129 __tmp.put_u8(self.id);
28130 if matches!(version, MavlinkVersion::V2) {
28131 let len = __tmp.len();
28132 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28133 } else {
28134 __tmp.len()
28135 }
28136 }
28137}
28138#[doc = "id: 12920"]
28139#[doc = "Temperature and humidity from hygrometer."]
28140#[derive(Debug, Clone, PartialEq)]
28141#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28142#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28143pub struct HYGROMETER_SENSOR_DATA {
28144 #[doc = "Temperature"]
28145 pub temperature: i16,
28146 #[doc = "Humidity"]
28147 pub humidity: u16,
28148 #[doc = "Hygrometer ID"]
28149 pub id: u8,
28150}
28151impl HYGROMETER_SENSOR_DATA {
28152 pub const ENCODED_LEN: usize = 5usize;
28153 pub const DEFAULT: Self = Self {
28154 temperature: 0_i16,
28155 humidity: 0_u16,
28156 id: 0_u8,
28157 };
28158 #[cfg(feature = "arbitrary")]
28159 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28160 use arbitrary::{Arbitrary, Unstructured};
28161 let mut buf = [0u8; 1024];
28162 rng.fill_bytes(&mut buf);
28163 let mut unstructured = Unstructured::new(&buf);
28164 Self::arbitrary(&mut unstructured).unwrap_or_default()
28165 }
28166}
28167impl Default for HYGROMETER_SENSOR_DATA {
28168 fn default() -> Self {
28169 Self::DEFAULT.clone()
28170 }
28171}
28172impl MessageData for HYGROMETER_SENSOR_DATA {
28173 type Message = MavMessage;
28174 const ID: u32 = 12920u32;
28175 const NAME: &'static str = "HYGROMETER_SENSOR";
28176 const EXTRA_CRC: u8 = 20u8;
28177 const ENCODED_LEN: usize = 5usize;
28178 fn deser(
28179 _version: MavlinkVersion,
28180 __input: &[u8],
28181 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28182 let avail_len = __input.len();
28183 let mut payload_buf = [0; Self::ENCODED_LEN];
28184 let mut buf = if avail_len < Self::ENCODED_LEN {
28185 payload_buf[0..avail_len].copy_from_slice(__input);
28186 Bytes::new(&payload_buf)
28187 } else {
28188 Bytes::new(__input)
28189 };
28190 let mut __struct = Self::default();
28191 __struct.temperature = buf.get_i16_le();
28192 __struct.humidity = buf.get_u16_le();
28193 __struct.id = buf.get_u8();
28194 Ok(__struct)
28195 }
28196 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28197 let mut __tmp = BytesMut::new(bytes);
28198 #[allow(clippy::absurd_extreme_comparisons)]
28199 #[allow(unused_comparisons)]
28200 if __tmp.remaining() < Self::ENCODED_LEN {
28201 panic!(
28202 "buffer is too small (need {} bytes, but got {})",
28203 Self::ENCODED_LEN,
28204 __tmp.remaining(),
28205 )
28206 }
28207 __tmp.put_i16_le(self.temperature);
28208 __tmp.put_u16_le(self.humidity);
28209 __tmp.put_u8(self.id);
28210 if matches!(version, MavlinkVersion::V2) {
28211 let len = __tmp.len();
28212 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28213 } else {
28214 __tmp.len()
28215 }
28216 }
28217}
28218#[doc = "id: 42"]
28219#[doc = "Message that announces the sequence number of the current target mission item (that the system will fly towards/execute when the mission is running). This message should be streamed all the time (nominally at 1Hz). This message should be emitted following a call to MAV_CMD_DO_SET_MISSION_CURRENT or MISSION_SET_CURRENT."]
28220#[derive(Debug, Clone, PartialEq)]
28221#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28222#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28223pub struct MISSION_CURRENT_DATA {
28224 #[doc = "Sequence"]
28225 pub seq: u16,
28226 #[doc = "Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle."]
28227 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28228 pub total: u16,
28229 #[doc = "Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported."]
28230 #[cfg_attr(feature = "serde", serde(default))]
28231 pub mission_state: MissionState,
28232 #[doc = "Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode)."]
28233 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28234 pub mission_mode: u8,
28235 #[doc = "Id of current on-vehicle mission plan, or 0 if IDs are not supported or there is no mission loaded. GCS can use this to track changes to the mission plan type. The same value is returned on mission upload (in the MISSION_ACK)."]
28236 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28237 pub mission_id: u32,
28238 #[doc = "Id of current on-vehicle fence plan, or 0 if IDs are not supported or there is no fence loaded. GCS can use this to track changes to the fence plan type. The same value is returned on fence upload (in the MISSION_ACK)."]
28239 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28240 pub fence_id: u32,
28241 #[doc = "Id of current on-vehicle rally point plan, or 0 if IDs are not supported or there are no rally points loaded. GCS can use this to track changes to the rally point plan type. The same value is returned on rally point upload (in the MISSION_ACK)."]
28242 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28243 pub rally_points_id: u32,
28244}
28245impl MISSION_CURRENT_DATA {
28246 pub const ENCODED_LEN: usize = 18usize;
28247 pub const DEFAULT: Self = Self {
28248 seq: 0_u16,
28249 total: 0_u16,
28250 mission_state: MissionState::DEFAULT,
28251 mission_mode: 0_u8,
28252 mission_id: 0_u32,
28253 fence_id: 0_u32,
28254 rally_points_id: 0_u32,
28255 };
28256 #[cfg(feature = "arbitrary")]
28257 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28258 use arbitrary::{Arbitrary, Unstructured};
28259 let mut buf = [0u8; 1024];
28260 rng.fill_bytes(&mut buf);
28261 let mut unstructured = Unstructured::new(&buf);
28262 Self::arbitrary(&mut unstructured).unwrap_or_default()
28263 }
28264}
28265impl Default for MISSION_CURRENT_DATA {
28266 fn default() -> Self {
28267 Self::DEFAULT.clone()
28268 }
28269}
28270impl MessageData for MISSION_CURRENT_DATA {
28271 type Message = MavMessage;
28272 const ID: u32 = 42u32;
28273 const NAME: &'static str = "MISSION_CURRENT";
28274 const EXTRA_CRC: u8 = 28u8;
28275 const ENCODED_LEN: usize = 18usize;
28276 fn deser(
28277 _version: MavlinkVersion,
28278 __input: &[u8],
28279 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28280 let avail_len = __input.len();
28281 let mut payload_buf = [0; Self::ENCODED_LEN];
28282 let mut buf = if avail_len < Self::ENCODED_LEN {
28283 payload_buf[0..avail_len].copy_from_slice(__input);
28284 Bytes::new(&payload_buf)
28285 } else {
28286 Bytes::new(__input)
28287 };
28288 let mut __struct = Self::default();
28289 __struct.seq = buf.get_u16_le();
28290 __struct.total = buf.get_u16_le();
28291 let tmp = buf.get_u8();
28292 __struct.mission_state =
28293 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28294 enum_type: "MissionState",
28295 value: tmp as u32,
28296 })?;
28297 __struct.mission_mode = buf.get_u8();
28298 __struct.mission_id = buf.get_u32_le();
28299 __struct.fence_id = buf.get_u32_le();
28300 __struct.rally_points_id = buf.get_u32_le();
28301 Ok(__struct)
28302 }
28303 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28304 let mut __tmp = BytesMut::new(bytes);
28305 #[allow(clippy::absurd_extreme_comparisons)]
28306 #[allow(unused_comparisons)]
28307 if __tmp.remaining() < Self::ENCODED_LEN {
28308 panic!(
28309 "buffer is too small (need {} bytes, but got {})",
28310 Self::ENCODED_LEN,
28311 __tmp.remaining(),
28312 )
28313 }
28314 __tmp.put_u16_le(self.seq);
28315 __tmp.put_u16_le(self.total);
28316 __tmp.put_u8(self.mission_state as u8);
28317 __tmp.put_u8(self.mission_mode);
28318 __tmp.put_u32_le(self.mission_id);
28319 __tmp.put_u32_le(self.fence_id);
28320 __tmp.put_u32_le(self.rally_points_id);
28321 if matches!(version, MavlinkVersion::V2) {
28322 let len = __tmp.len();
28323 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28324 } else {
28325 __tmp.len()
28326 }
28327 }
28328}
28329#[doc = "id: 437"]
28330#[doc = "A change to the sequence number indicates that the set of AVAILABLE_MODES has changed. A receiver must re-request all available modes whenever the sequence number changes. This is only emitted after the first change and should then be broadcast at low rate (nominally 0.3 Hz) and on change. See <https://mavlink.io/en/services/standard_modes.html>."]
28331#[derive(Debug, Clone, PartialEq)]
28332#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28333#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28334pub struct AVAILABLE_MODES_MONITOR_DATA {
28335 #[doc = "Sequence number. The value iterates sequentially whenever AVAILABLE_MODES changes (e.g. support for a new mode is added/removed dynamically)."]
28336 pub seq: u8,
28337}
28338impl AVAILABLE_MODES_MONITOR_DATA {
28339 pub const ENCODED_LEN: usize = 1usize;
28340 pub const DEFAULT: Self = Self { seq: 0_u8 };
28341 #[cfg(feature = "arbitrary")]
28342 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28343 use arbitrary::{Arbitrary, Unstructured};
28344 let mut buf = [0u8; 1024];
28345 rng.fill_bytes(&mut buf);
28346 let mut unstructured = Unstructured::new(&buf);
28347 Self::arbitrary(&mut unstructured).unwrap_or_default()
28348 }
28349}
28350impl Default for AVAILABLE_MODES_MONITOR_DATA {
28351 fn default() -> Self {
28352 Self::DEFAULT.clone()
28353 }
28354}
28355impl MessageData for AVAILABLE_MODES_MONITOR_DATA {
28356 type Message = MavMessage;
28357 const ID: u32 = 437u32;
28358 const NAME: &'static str = "AVAILABLE_MODES_MONITOR";
28359 const EXTRA_CRC: u8 = 30u8;
28360 const ENCODED_LEN: usize = 1usize;
28361 fn deser(
28362 _version: MavlinkVersion,
28363 __input: &[u8],
28364 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28365 let avail_len = __input.len();
28366 let mut payload_buf = [0; Self::ENCODED_LEN];
28367 let mut buf = if avail_len < Self::ENCODED_LEN {
28368 payload_buf[0..avail_len].copy_from_slice(__input);
28369 Bytes::new(&payload_buf)
28370 } else {
28371 Bytes::new(__input)
28372 };
28373 let mut __struct = Self::default();
28374 __struct.seq = buf.get_u8();
28375 Ok(__struct)
28376 }
28377 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28378 let mut __tmp = BytesMut::new(bytes);
28379 #[allow(clippy::absurd_extreme_comparisons)]
28380 #[allow(unused_comparisons)]
28381 if __tmp.remaining() < Self::ENCODED_LEN {
28382 panic!(
28383 "buffer is too small (need {} bytes, but got {})",
28384 Self::ENCODED_LEN,
28385 __tmp.remaining(),
28386 )
28387 }
28388 __tmp.put_u8(self.seq);
28389 if matches!(version, MavlinkVersion::V2) {
28390 let len = __tmp.len();
28391 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28392 } else {
28393 __tmp.len()
28394 }
28395 }
28396}
28397#[doc = "id: 125"]
28398#[doc = "Power supply status."]
28399#[derive(Debug, Clone, PartialEq)]
28400#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28401#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28402pub struct POWER_STATUS_DATA {
28403 #[doc = "5V rail voltage."]
28404 pub Vcc: u16,
28405 #[doc = "Servo rail voltage."]
28406 pub Vservo: u16,
28407 #[doc = "Bitmap of power supply status flags."]
28408 pub flags: MavPowerStatus,
28409}
28410impl POWER_STATUS_DATA {
28411 pub const ENCODED_LEN: usize = 6usize;
28412 pub const DEFAULT: Self = Self {
28413 Vcc: 0_u16,
28414 Vservo: 0_u16,
28415 flags: MavPowerStatus::DEFAULT,
28416 };
28417 #[cfg(feature = "arbitrary")]
28418 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28419 use arbitrary::{Arbitrary, Unstructured};
28420 let mut buf = [0u8; 1024];
28421 rng.fill_bytes(&mut buf);
28422 let mut unstructured = Unstructured::new(&buf);
28423 Self::arbitrary(&mut unstructured).unwrap_or_default()
28424 }
28425}
28426impl Default for POWER_STATUS_DATA {
28427 fn default() -> Self {
28428 Self::DEFAULT.clone()
28429 }
28430}
28431impl MessageData for POWER_STATUS_DATA {
28432 type Message = MavMessage;
28433 const ID: u32 = 125u32;
28434 const NAME: &'static str = "POWER_STATUS";
28435 const EXTRA_CRC: u8 = 203u8;
28436 const ENCODED_LEN: usize = 6usize;
28437 fn deser(
28438 _version: MavlinkVersion,
28439 __input: &[u8],
28440 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28441 let avail_len = __input.len();
28442 let mut payload_buf = [0; Self::ENCODED_LEN];
28443 let mut buf = if avail_len < Self::ENCODED_LEN {
28444 payload_buf[0..avail_len].copy_from_slice(__input);
28445 Bytes::new(&payload_buf)
28446 } else {
28447 Bytes::new(__input)
28448 };
28449 let mut __struct = Self::default();
28450 __struct.Vcc = buf.get_u16_le();
28451 __struct.Vservo = buf.get_u16_le();
28452 let tmp = buf.get_u16_le();
28453 __struct.flags = MavPowerStatus::from_bits(tmp & MavPowerStatus::all().bits()).ok_or(
28454 ::mavlink_core::error::ParserError::InvalidFlag {
28455 flag_type: "MavPowerStatus",
28456 value: tmp as u32,
28457 },
28458 )?;
28459 Ok(__struct)
28460 }
28461 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28462 let mut __tmp = BytesMut::new(bytes);
28463 #[allow(clippy::absurd_extreme_comparisons)]
28464 #[allow(unused_comparisons)]
28465 if __tmp.remaining() < Self::ENCODED_LEN {
28466 panic!(
28467 "buffer is too small (need {} bytes, but got {})",
28468 Self::ENCODED_LEN,
28469 __tmp.remaining(),
28470 )
28471 }
28472 __tmp.put_u16_le(self.Vcc);
28473 __tmp.put_u16_le(self.Vservo);
28474 __tmp.put_u16_le(self.flags.bits());
28475 if matches!(version, MavlinkVersion::V2) {
28476 let len = __tmp.len();
28477 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28478 } else {
28479 __tmp.len()
28480 }
28481 }
28482}
28483#[doc = "id: 339"]
28484#[doc = "RPM sensor data message."]
28485#[derive(Debug, Clone, PartialEq)]
28486#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28487#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28488pub struct RAW_RPM_DATA {
28489 #[doc = "Indicated rate"]
28490 pub frequency: f32,
28491 #[doc = "Index of this RPM sensor (0-indexed)"]
28492 pub index: u8,
28493}
28494impl RAW_RPM_DATA {
28495 pub const ENCODED_LEN: usize = 5usize;
28496 pub const DEFAULT: Self = Self {
28497 frequency: 0.0_f32,
28498 index: 0_u8,
28499 };
28500 #[cfg(feature = "arbitrary")]
28501 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28502 use arbitrary::{Arbitrary, Unstructured};
28503 let mut buf = [0u8; 1024];
28504 rng.fill_bytes(&mut buf);
28505 let mut unstructured = Unstructured::new(&buf);
28506 Self::arbitrary(&mut unstructured).unwrap_or_default()
28507 }
28508}
28509impl Default for RAW_RPM_DATA {
28510 fn default() -> Self {
28511 Self::DEFAULT.clone()
28512 }
28513}
28514impl MessageData for RAW_RPM_DATA {
28515 type Message = MavMessage;
28516 const ID: u32 = 339u32;
28517 const NAME: &'static str = "RAW_RPM";
28518 const EXTRA_CRC: u8 = 199u8;
28519 const ENCODED_LEN: usize = 5usize;
28520 fn deser(
28521 _version: MavlinkVersion,
28522 __input: &[u8],
28523 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28524 let avail_len = __input.len();
28525 let mut payload_buf = [0; Self::ENCODED_LEN];
28526 let mut buf = if avail_len < Self::ENCODED_LEN {
28527 payload_buf[0..avail_len].copy_from_slice(__input);
28528 Bytes::new(&payload_buf)
28529 } else {
28530 Bytes::new(__input)
28531 };
28532 let mut __struct = Self::default();
28533 __struct.frequency = buf.get_f32_le();
28534 __struct.index = buf.get_u8();
28535 Ok(__struct)
28536 }
28537 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28538 let mut __tmp = BytesMut::new(bytes);
28539 #[allow(clippy::absurd_extreme_comparisons)]
28540 #[allow(unused_comparisons)]
28541 if __tmp.remaining() < Self::ENCODED_LEN {
28542 panic!(
28543 "buffer is too small (need {} bytes, but got {})",
28544 Self::ENCODED_LEN,
28545 __tmp.remaining(),
28546 )
28547 }
28548 __tmp.put_f32_le(self.frequency);
28549 __tmp.put_u8(self.index);
28550 if matches!(version, MavlinkVersion::V2) {
28551 let len = __tmp.len();
28552 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28553 } else {
28554 __tmp.len()
28555 }
28556 }
28557}
28558#[doc = "id: 288"]
28559#[doc = "High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case."]
28560#[derive(Debug, Clone, PartialEq)]
28561#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28562#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28563pub struct GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
28564 #[doc = "High level gimbal manager flags."]
28565 pub flags: GimbalManagerFlags,
28566 #[doc = "Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored)."]
28567 pub pitch: f32,
28568 #[doc = "Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored)."]
28569 pub yaw: f32,
28570 #[doc = "Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored)."]
28571 pub pitch_rate: f32,
28572 #[doc = "Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored)."]
28573 pub yaw_rate: f32,
28574 #[doc = "System ID"]
28575 pub target_system: u8,
28576 #[doc = "Component ID"]
28577 pub target_component: u8,
28578 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
28579 pub gimbal_device_id: u8,
28580}
28581impl GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
28582 pub const ENCODED_LEN: usize = 23usize;
28583 pub const DEFAULT: Self = Self {
28584 flags: GimbalManagerFlags::DEFAULT,
28585 pitch: 0.0_f32,
28586 yaw: 0.0_f32,
28587 pitch_rate: 0.0_f32,
28588 yaw_rate: 0.0_f32,
28589 target_system: 0_u8,
28590 target_component: 0_u8,
28591 gimbal_device_id: 0_u8,
28592 };
28593 #[cfg(feature = "arbitrary")]
28594 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28595 use arbitrary::{Arbitrary, Unstructured};
28596 let mut buf = [0u8; 1024];
28597 rng.fill_bytes(&mut buf);
28598 let mut unstructured = Unstructured::new(&buf);
28599 Self::arbitrary(&mut unstructured).unwrap_or_default()
28600 }
28601}
28602impl Default for GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
28603 fn default() -> Self {
28604 Self::DEFAULT.clone()
28605 }
28606}
28607impl MessageData for GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
28608 type Message = MavMessage;
28609 const ID: u32 = 288u32;
28610 const NAME: &'static str = "GIMBAL_MANAGER_SET_MANUAL_CONTROL";
28611 const EXTRA_CRC: u8 = 20u8;
28612 const ENCODED_LEN: usize = 23usize;
28613 fn deser(
28614 _version: MavlinkVersion,
28615 __input: &[u8],
28616 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28617 let avail_len = __input.len();
28618 let mut payload_buf = [0; Self::ENCODED_LEN];
28619 let mut buf = if avail_len < Self::ENCODED_LEN {
28620 payload_buf[0..avail_len].copy_from_slice(__input);
28621 Bytes::new(&payload_buf)
28622 } else {
28623 Bytes::new(__input)
28624 };
28625 let mut __struct = Self::default();
28626 let tmp = buf.get_u32_le();
28627 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
28628 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28629 flag_type: "GimbalManagerFlags",
28630 value: tmp as u32,
28631 })?;
28632 __struct.pitch = buf.get_f32_le();
28633 __struct.yaw = buf.get_f32_le();
28634 __struct.pitch_rate = buf.get_f32_le();
28635 __struct.yaw_rate = buf.get_f32_le();
28636 __struct.target_system = buf.get_u8();
28637 __struct.target_component = buf.get_u8();
28638 __struct.gimbal_device_id = buf.get_u8();
28639 Ok(__struct)
28640 }
28641 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28642 let mut __tmp = BytesMut::new(bytes);
28643 #[allow(clippy::absurd_extreme_comparisons)]
28644 #[allow(unused_comparisons)]
28645 if __tmp.remaining() < Self::ENCODED_LEN {
28646 panic!(
28647 "buffer is too small (need {} bytes, but got {})",
28648 Self::ENCODED_LEN,
28649 __tmp.remaining(),
28650 )
28651 }
28652 __tmp.put_u32_le(self.flags.bits());
28653 __tmp.put_f32_le(self.pitch);
28654 __tmp.put_f32_le(self.yaw);
28655 __tmp.put_f32_le(self.pitch_rate);
28656 __tmp.put_f32_le(self.yaw_rate);
28657 __tmp.put_u8(self.target_system);
28658 __tmp.put_u8(self.target_component);
28659 __tmp.put_u8(self.gimbal_device_id);
28660 if matches!(version, MavlinkVersion::V2) {
28661 let len = __tmp.len();
28662 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28663 } else {
28664 __tmp.len()
28665 }
28666 }
28667}
28668#[doc = "id: 10005"]
28669#[doc = "Flight Identification for ADSB-Out vehicles."]
28670#[derive(Debug, Clone, PartialEq)]
28671#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28672#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28673pub struct UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA {
28674 #[doc = "Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. Reflects Control message setting. This is null-terminated."]
28675 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28676 pub flight_id: [u8; 9],
28677}
28678impl UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA {
28679 pub const ENCODED_LEN: usize = 9usize;
28680 pub const DEFAULT: Self = Self {
28681 flight_id: [0_u8; 9usize],
28682 };
28683 #[cfg(feature = "arbitrary")]
28684 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28685 use arbitrary::{Arbitrary, Unstructured};
28686 let mut buf = [0u8; 1024];
28687 rng.fill_bytes(&mut buf);
28688 let mut unstructured = Unstructured::new(&buf);
28689 Self::arbitrary(&mut unstructured).unwrap_or_default()
28690 }
28691}
28692impl Default for UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA {
28693 fn default() -> Self {
28694 Self::DEFAULT.clone()
28695 }
28696}
28697impl MessageData for UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA {
28698 type Message = MavMessage;
28699 const ID: u32 = 10005u32;
28700 const NAME: &'static str = "UAVIONIX_ADSB_OUT_CFG_FLIGHTID";
28701 const EXTRA_CRC: u8 = 103u8;
28702 const ENCODED_LEN: usize = 9usize;
28703 fn deser(
28704 _version: MavlinkVersion,
28705 __input: &[u8],
28706 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28707 let avail_len = __input.len();
28708 let mut payload_buf = [0; Self::ENCODED_LEN];
28709 let mut buf = if avail_len < Self::ENCODED_LEN {
28710 payload_buf[0..avail_len].copy_from_slice(__input);
28711 Bytes::new(&payload_buf)
28712 } else {
28713 Bytes::new(__input)
28714 };
28715 let mut __struct = Self::default();
28716 for v in &mut __struct.flight_id {
28717 let val = buf.get_u8();
28718 *v = val;
28719 }
28720 Ok(__struct)
28721 }
28722 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28723 let mut __tmp = BytesMut::new(bytes);
28724 #[allow(clippy::absurd_extreme_comparisons)]
28725 #[allow(unused_comparisons)]
28726 if __tmp.remaining() < Self::ENCODED_LEN {
28727 panic!(
28728 "buffer is too small (need {} bytes, but got {})",
28729 Self::ENCODED_LEN,
28730 __tmp.remaining(),
28731 )
28732 }
28733 for val in &self.flight_id {
28734 __tmp.put_u8(*val);
28735 }
28736 if matches!(version, MavlinkVersion::V2) {
28737 let len = __tmp.len();
28738 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28739 } else {
28740 __tmp.len()
28741 }
28742 }
28743}
28744#[doc = "id: 32"]
28745#[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
28746#[derive(Debug, Clone, PartialEq)]
28747#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28748#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28749pub struct LOCAL_POSITION_NED_DATA {
28750 #[doc = "Timestamp (time since system boot)."]
28751 pub time_boot_ms: u32,
28752 #[doc = "X Position"]
28753 pub x: f32,
28754 #[doc = "Y Position"]
28755 pub y: f32,
28756 #[doc = "Z Position"]
28757 pub z: f32,
28758 #[doc = "X Speed"]
28759 pub vx: f32,
28760 #[doc = "Y Speed"]
28761 pub vy: f32,
28762 #[doc = "Z Speed"]
28763 pub vz: f32,
28764}
28765impl LOCAL_POSITION_NED_DATA {
28766 pub const ENCODED_LEN: usize = 28usize;
28767 pub const DEFAULT: Self = Self {
28768 time_boot_ms: 0_u32,
28769 x: 0.0_f32,
28770 y: 0.0_f32,
28771 z: 0.0_f32,
28772 vx: 0.0_f32,
28773 vy: 0.0_f32,
28774 vz: 0.0_f32,
28775 };
28776 #[cfg(feature = "arbitrary")]
28777 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28778 use arbitrary::{Arbitrary, Unstructured};
28779 let mut buf = [0u8; 1024];
28780 rng.fill_bytes(&mut buf);
28781 let mut unstructured = Unstructured::new(&buf);
28782 Self::arbitrary(&mut unstructured).unwrap_or_default()
28783 }
28784}
28785impl Default for LOCAL_POSITION_NED_DATA {
28786 fn default() -> Self {
28787 Self::DEFAULT.clone()
28788 }
28789}
28790impl MessageData for LOCAL_POSITION_NED_DATA {
28791 type Message = MavMessage;
28792 const ID: u32 = 32u32;
28793 const NAME: &'static str = "LOCAL_POSITION_NED";
28794 const EXTRA_CRC: u8 = 185u8;
28795 const ENCODED_LEN: usize = 28usize;
28796 fn deser(
28797 _version: MavlinkVersion,
28798 __input: &[u8],
28799 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28800 let avail_len = __input.len();
28801 let mut payload_buf = [0; Self::ENCODED_LEN];
28802 let mut buf = if avail_len < Self::ENCODED_LEN {
28803 payload_buf[0..avail_len].copy_from_slice(__input);
28804 Bytes::new(&payload_buf)
28805 } else {
28806 Bytes::new(__input)
28807 };
28808 let mut __struct = Self::default();
28809 __struct.time_boot_ms = buf.get_u32_le();
28810 __struct.x = buf.get_f32_le();
28811 __struct.y = buf.get_f32_le();
28812 __struct.z = buf.get_f32_le();
28813 __struct.vx = buf.get_f32_le();
28814 __struct.vy = buf.get_f32_le();
28815 __struct.vz = buf.get_f32_le();
28816 Ok(__struct)
28817 }
28818 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28819 let mut __tmp = BytesMut::new(bytes);
28820 #[allow(clippy::absurd_extreme_comparisons)]
28821 #[allow(unused_comparisons)]
28822 if __tmp.remaining() < Self::ENCODED_LEN {
28823 panic!(
28824 "buffer is too small (need {} bytes, but got {})",
28825 Self::ENCODED_LEN,
28826 __tmp.remaining(),
28827 )
28828 }
28829 __tmp.put_u32_le(self.time_boot_ms);
28830 __tmp.put_f32_le(self.x);
28831 __tmp.put_f32_le(self.y);
28832 __tmp.put_f32_le(self.z);
28833 __tmp.put_f32_le(self.vx);
28834 __tmp.put_f32_le(self.vy);
28835 __tmp.put_f32_le(self.vz);
28836 if matches!(version, MavlinkVersion::V2) {
28837 let len = __tmp.len();
28838 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28839 } else {
28840 __tmp.len()
28841 }
28842 }
28843}
28844#[doc = "id: 27"]
28845#[doc = "The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging."]
28846#[derive(Debug, Clone, PartialEq)]
28847#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28848#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28849pub struct RAW_IMU_DATA {
28850 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
28851 pub time_usec: u64,
28852 #[doc = "X acceleration (raw)"]
28853 pub xacc: i16,
28854 #[doc = "Y acceleration (raw)"]
28855 pub yacc: i16,
28856 #[doc = "Z acceleration (raw)"]
28857 pub zacc: i16,
28858 #[doc = "Angular speed around X axis (raw)"]
28859 pub xgyro: i16,
28860 #[doc = "Angular speed around Y axis (raw)"]
28861 pub ygyro: i16,
28862 #[doc = "Angular speed around Z axis (raw)"]
28863 pub zgyro: i16,
28864 #[doc = "X Magnetic field (raw)"]
28865 pub xmag: i16,
28866 #[doc = "Y Magnetic field (raw)"]
28867 pub ymag: i16,
28868 #[doc = "Z Magnetic field (raw)"]
28869 pub zmag: i16,
28870 #[doc = "Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)"]
28871 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28872 pub id: u8,
28873 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
28874 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28875 pub temperature: i16,
28876}
28877impl RAW_IMU_DATA {
28878 pub const ENCODED_LEN: usize = 29usize;
28879 pub const DEFAULT: Self = Self {
28880 time_usec: 0_u64,
28881 xacc: 0_i16,
28882 yacc: 0_i16,
28883 zacc: 0_i16,
28884 xgyro: 0_i16,
28885 ygyro: 0_i16,
28886 zgyro: 0_i16,
28887 xmag: 0_i16,
28888 ymag: 0_i16,
28889 zmag: 0_i16,
28890 id: 0_u8,
28891 temperature: 0_i16,
28892 };
28893 #[cfg(feature = "arbitrary")]
28894 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28895 use arbitrary::{Arbitrary, Unstructured};
28896 let mut buf = [0u8; 1024];
28897 rng.fill_bytes(&mut buf);
28898 let mut unstructured = Unstructured::new(&buf);
28899 Self::arbitrary(&mut unstructured).unwrap_or_default()
28900 }
28901}
28902impl Default for RAW_IMU_DATA {
28903 fn default() -> Self {
28904 Self::DEFAULT.clone()
28905 }
28906}
28907impl MessageData for RAW_IMU_DATA {
28908 type Message = MavMessage;
28909 const ID: u32 = 27u32;
28910 const NAME: &'static str = "RAW_IMU";
28911 const EXTRA_CRC: u8 = 144u8;
28912 const ENCODED_LEN: usize = 29usize;
28913 fn deser(
28914 _version: MavlinkVersion,
28915 __input: &[u8],
28916 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28917 let avail_len = __input.len();
28918 let mut payload_buf = [0; Self::ENCODED_LEN];
28919 let mut buf = if avail_len < Self::ENCODED_LEN {
28920 payload_buf[0..avail_len].copy_from_slice(__input);
28921 Bytes::new(&payload_buf)
28922 } else {
28923 Bytes::new(__input)
28924 };
28925 let mut __struct = Self::default();
28926 __struct.time_usec = buf.get_u64_le();
28927 __struct.xacc = buf.get_i16_le();
28928 __struct.yacc = buf.get_i16_le();
28929 __struct.zacc = buf.get_i16_le();
28930 __struct.xgyro = buf.get_i16_le();
28931 __struct.ygyro = buf.get_i16_le();
28932 __struct.zgyro = buf.get_i16_le();
28933 __struct.xmag = buf.get_i16_le();
28934 __struct.ymag = buf.get_i16_le();
28935 __struct.zmag = buf.get_i16_le();
28936 __struct.id = buf.get_u8();
28937 __struct.temperature = buf.get_i16_le();
28938 Ok(__struct)
28939 }
28940 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28941 let mut __tmp = BytesMut::new(bytes);
28942 #[allow(clippy::absurd_extreme_comparisons)]
28943 #[allow(unused_comparisons)]
28944 if __tmp.remaining() < Self::ENCODED_LEN {
28945 panic!(
28946 "buffer is too small (need {} bytes, but got {})",
28947 Self::ENCODED_LEN,
28948 __tmp.remaining(),
28949 )
28950 }
28951 __tmp.put_u64_le(self.time_usec);
28952 __tmp.put_i16_le(self.xacc);
28953 __tmp.put_i16_le(self.yacc);
28954 __tmp.put_i16_le(self.zacc);
28955 __tmp.put_i16_le(self.xgyro);
28956 __tmp.put_i16_le(self.ygyro);
28957 __tmp.put_i16_le(self.zgyro);
28958 __tmp.put_i16_le(self.xmag);
28959 __tmp.put_i16_le(self.ymag);
28960 __tmp.put_i16_le(self.zmag);
28961 __tmp.put_u8(self.id);
28962 __tmp.put_i16_le(self.temperature);
28963 if matches!(version, MavlinkVersion::V2) {
28964 let len = __tmp.len();
28965 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28966 } else {
28967 __tmp.len()
28968 }
28969 }
28970}
28971#[doc = "id: 23"]
28972#[doc = "Set a parameter value (write new value to permanent storage). The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
28973#[derive(Debug, Clone, PartialEq)]
28974#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28975#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28976pub struct PARAM_SET_DATA {
28977 #[doc = "Onboard parameter value"]
28978 pub param_value: f32,
28979 #[doc = "System ID"]
28980 pub target_system: u8,
28981 #[doc = "Component ID"]
28982 pub target_component: u8,
28983 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
28984 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28985 pub param_id: [u8; 16],
28986 #[doc = "Onboard parameter type."]
28987 pub param_type: MavParamType,
28988}
28989impl PARAM_SET_DATA {
28990 pub const ENCODED_LEN: usize = 23usize;
28991 pub const DEFAULT: Self = Self {
28992 param_value: 0.0_f32,
28993 target_system: 0_u8,
28994 target_component: 0_u8,
28995 param_id: [0_u8; 16usize],
28996 param_type: MavParamType::DEFAULT,
28997 };
28998 #[cfg(feature = "arbitrary")]
28999 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29000 use arbitrary::{Arbitrary, Unstructured};
29001 let mut buf = [0u8; 1024];
29002 rng.fill_bytes(&mut buf);
29003 let mut unstructured = Unstructured::new(&buf);
29004 Self::arbitrary(&mut unstructured).unwrap_or_default()
29005 }
29006}
29007impl Default for PARAM_SET_DATA {
29008 fn default() -> Self {
29009 Self::DEFAULT.clone()
29010 }
29011}
29012impl MessageData for PARAM_SET_DATA {
29013 type Message = MavMessage;
29014 const ID: u32 = 23u32;
29015 const NAME: &'static str = "PARAM_SET";
29016 const EXTRA_CRC: u8 = 168u8;
29017 const ENCODED_LEN: usize = 23usize;
29018 fn deser(
29019 _version: MavlinkVersion,
29020 __input: &[u8],
29021 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29022 let avail_len = __input.len();
29023 let mut payload_buf = [0; Self::ENCODED_LEN];
29024 let mut buf = if avail_len < Self::ENCODED_LEN {
29025 payload_buf[0..avail_len].copy_from_slice(__input);
29026 Bytes::new(&payload_buf)
29027 } else {
29028 Bytes::new(__input)
29029 };
29030 let mut __struct = Self::default();
29031 __struct.param_value = buf.get_f32_le();
29032 __struct.target_system = buf.get_u8();
29033 __struct.target_component = buf.get_u8();
29034 for v in &mut __struct.param_id {
29035 let val = buf.get_u8();
29036 *v = val;
29037 }
29038 let tmp = buf.get_u8();
29039 __struct.param_type =
29040 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29041 enum_type: "MavParamType",
29042 value: tmp as u32,
29043 })?;
29044 Ok(__struct)
29045 }
29046 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29047 let mut __tmp = BytesMut::new(bytes);
29048 #[allow(clippy::absurd_extreme_comparisons)]
29049 #[allow(unused_comparisons)]
29050 if __tmp.remaining() < Self::ENCODED_LEN {
29051 panic!(
29052 "buffer is too small (need {} bytes, but got {})",
29053 Self::ENCODED_LEN,
29054 __tmp.remaining(),
29055 )
29056 }
29057 __tmp.put_f32_le(self.param_value);
29058 __tmp.put_u8(self.target_system);
29059 __tmp.put_u8(self.target_component);
29060 for val in &self.param_id {
29061 __tmp.put_u8(*val);
29062 }
29063 __tmp.put_u8(self.param_type as u8);
29064 if matches!(version, MavlinkVersion::V2) {
29065 let len = __tmp.len();
29066 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29067 } else {
29068 __tmp.len()
29069 }
29070 }
29071}
29072#[doc = "id: 40"]
29073#[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. <https://mavlink.io/en/services/mission.html>."]
29074#[derive(Debug, Clone, PartialEq)]
29075#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29076#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29077pub struct MISSION_REQUEST_DATA {
29078 #[doc = "Sequence"]
29079 pub seq: u16,
29080 #[doc = "System ID"]
29081 pub target_system: u8,
29082 #[doc = "Component ID"]
29083 pub target_component: u8,
29084 #[doc = "Mission type."]
29085 #[cfg_attr(feature = "serde", serde(default))]
29086 pub mission_type: MavMissionType,
29087}
29088impl MISSION_REQUEST_DATA {
29089 pub const ENCODED_LEN: usize = 5usize;
29090 pub const DEFAULT: Self = Self {
29091 seq: 0_u16,
29092 target_system: 0_u8,
29093 target_component: 0_u8,
29094 mission_type: MavMissionType::DEFAULT,
29095 };
29096 #[cfg(feature = "arbitrary")]
29097 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29098 use arbitrary::{Arbitrary, Unstructured};
29099 let mut buf = [0u8; 1024];
29100 rng.fill_bytes(&mut buf);
29101 let mut unstructured = Unstructured::new(&buf);
29102 Self::arbitrary(&mut unstructured).unwrap_or_default()
29103 }
29104}
29105impl Default for MISSION_REQUEST_DATA {
29106 fn default() -> Self {
29107 Self::DEFAULT.clone()
29108 }
29109}
29110impl MessageData for MISSION_REQUEST_DATA {
29111 type Message = MavMessage;
29112 const ID: u32 = 40u32;
29113 const NAME: &'static str = "MISSION_REQUEST";
29114 const EXTRA_CRC: u8 = 230u8;
29115 const ENCODED_LEN: usize = 5usize;
29116 fn deser(
29117 _version: MavlinkVersion,
29118 __input: &[u8],
29119 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29120 let avail_len = __input.len();
29121 let mut payload_buf = [0; Self::ENCODED_LEN];
29122 let mut buf = if avail_len < Self::ENCODED_LEN {
29123 payload_buf[0..avail_len].copy_from_slice(__input);
29124 Bytes::new(&payload_buf)
29125 } else {
29126 Bytes::new(__input)
29127 };
29128 let mut __struct = Self::default();
29129 __struct.seq = buf.get_u16_le();
29130 __struct.target_system = buf.get_u8();
29131 __struct.target_component = buf.get_u8();
29132 let tmp = buf.get_u8();
29133 __struct.mission_type =
29134 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29135 enum_type: "MavMissionType",
29136 value: tmp as u32,
29137 })?;
29138 Ok(__struct)
29139 }
29140 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29141 let mut __tmp = BytesMut::new(bytes);
29142 #[allow(clippy::absurd_extreme_comparisons)]
29143 #[allow(unused_comparisons)]
29144 if __tmp.remaining() < Self::ENCODED_LEN {
29145 panic!(
29146 "buffer is too small (need {} bytes, but got {})",
29147 Self::ENCODED_LEN,
29148 __tmp.remaining(),
29149 )
29150 }
29151 __tmp.put_u16_le(self.seq);
29152 __tmp.put_u8(self.target_system);
29153 __tmp.put_u8(self.target_component);
29154 __tmp.put_u8(self.mission_type as u8);
29155 if matches!(version, MavlinkVersion::V2) {
29156 let len = __tmp.len();
29157 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29158 } else {
29159 __tmp.len()
29160 }
29161 }
29162}
29163#[doc = "id: 55"]
29164#[doc = "Read out the safety zone the MAV currently assumes."]
29165#[derive(Debug, Clone, PartialEq)]
29166#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29167#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29168pub struct SAFETY_ALLOWED_AREA_DATA {
29169 #[doc = "x position 1 / Latitude 1"]
29170 pub p1x: f32,
29171 #[doc = "y position 1 / Longitude 1"]
29172 pub p1y: f32,
29173 #[doc = "z position 1 / Altitude 1"]
29174 pub p1z: f32,
29175 #[doc = "x position 2 / Latitude 2"]
29176 pub p2x: f32,
29177 #[doc = "y position 2 / Longitude 2"]
29178 pub p2y: f32,
29179 #[doc = "z position 2 / Altitude 2"]
29180 pub p2z: f32,
29181 #[doc = "Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down."]
29182 pub frame: MavFrame,
29183}
29184impl SAFETY_ALLOWED_AREA_DATA {
29185 pub const ENCODED_LEN: usize = 25usize;
29186 pub const DEFAULT: Self = Self {
29187 p1x: 0.0_f32,
29188 p1y: 0.0_f32,
29189 p1z: 0.0_f32,
29190 p2x: 0.0_f32,
29191 p2y: 0.0_f32,
29192 p2z: 0.0_f32,
29193 frame: MavFrame::DEFAULT,
29194 };
29195 #[cfg(feature = "arbitrary")]
29196 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29197 use arbitrary::{Arbitrary, Unstructured};
29198 let mut buf = [0u8; 1024];
29199 rng.fill_bytes(&mut buf);
29200 let mut unstructured = Unstructured::new(&buf);
29201 Self::arbitrary(&mut unstructured).unwrap_or_default()
29202 }
29203}
29204impl Default for SAFETY_ALLOWED_AREA_DATA {
29205 fn default() -> Self {
29206 Self::DEFAULT.clone()
29207 }
29208}
29209impl MessageData for SAFETY_ALLOWED_AREA_DATA {
29210 type Message = MavMessage;
29211 const ID: u32 = 55u32;
29212 const NAME: &'static str = "SAFETY_ALLOWED_AREA";
29213 const EXTRA_CRC: u8 = 3u8;
29214 const ENCODED_LEN: usize = 25usize;
29215 fn deser(
29216 _version: MavlinkVersion,
29217 __input: &[u8],
29218 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29219 let avail_len = __input.len();
29220 let mut payload_buf = [0; Self::ENCODED_LEN];
29221 let mut buf = if avail_len < Self::ENCODED_LEN {
29222 payload_buf[0..avail_len].copy_from_slice(__input);
29223 Bytes::new(&payload_buf)
29224 } else {
29225 Bytes::new(__input)
29226 };
29227 let mut __struct = Self::default();
29228 __struct.p1x = buf.get_f32_le();
29229 __struct.p1y = buf.get_f32_le();
29230 __struct.p1z = buf.get_f32_le();
29231 __struct.p2x = buf.get_f32_le();
29232 __struct.p2y = buf.get_f32_le();
29233 __struct.p2z = buf.get_f32_le();
29234 let tmp = buf.get_u8();
29235 __struct.frame =
29236 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29237 enum_type: "MavFrame",
29238 value: tmp as u32,
29239 })?;
29240 Ok(__struct)
29241 }
29242 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29243 let mut __tmp = BytesMut::new(bytes);
29244 #[allow(clippy::absurd_extreme_comparisons)]
29245 #[allow(unused_comparisons)]
29246 if __tmp.remaining() < Self::ENCODED_LEN {
29247 panic!(
29248 "buffer is too small (need {} bytes, but got {})",
29249 Self::ENCODED_LEN,
29250 __tmp.remaining(),
29251 )
29252 }
29253 __tmp.put_f32_le(self.p1x);
29254 __tmp.put_f32_le(self.p1y);
29255 __tmp.put_f32_le(self.p1z);
29256 __tmp.put_f32_le(self.p2x);
29257 __tmp.put_f32_le(self.p2y);
29258 __tmp.put_f32_le(self.p2z);
29259 __tmp.put_u8(self.frame as u8);
29260 if matches!(version, MavlinkVersion::V2) {
29261 let len = __tmp.len();
29262 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29263 } else {
29264 __tmp.len()
29265 }
29266 }
29267}
29268#[doc = "id: 285"]
29269#[doc = "Message reporting the status of a gimbal device. \t This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Other conditions of the flags are not allowed. \t The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as \t q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). \t If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, \t then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, \t and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN."]
29270#[derive(Debug, Clone, PartialEq)]
29271#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29272#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29273pub struct GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
29274 #[doc = "Timestamp (time since system boot)."]
29275 pub time_boot_ms: u32,
29276 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description."]
29277 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29278 pub q: [f32; 4],
29279 #[doc = "X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown."]
29280 pub angular_velocity_x: f32,
29281 #[doc = "Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown."]
29282 pub angular_velocity_y: f32,
29283 #[doc = "Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown."]
29284 pub angular_velocity_z: f32,
29285 #[doc = "Failure flags (0 for no failure)"]
29286 pub failure_flags: GimbalDeviceErrorFlags,
29287 #[doc = "Current gimbal flags set."]
29288 pub flags: GimbalDeviceFlags,
29289 #[doc = "System ID"]
29290 pub target_system: u8,
29291 #[doc = "Component ID"]
29292 pub target_component: u8,
29293 #[doc = "Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown."]
29294 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29295 pub delta_yaw: f32,
29296 #[doc = "Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown."]
29297 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29298 pub delta_yaw_velocity: f32,
29299 #[doc = "This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0."]
29300 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29301 pub gimbal_device_id: u8,
29302}
29303impl GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
29304 pub const ENCODED_LEN: usize = 49usize;
29305 pub const DEFAULT: Self = Self {
29306 time_boot_ms: 0_u32,
29307 q: [0.0_f32; 4usize],
29308 angular_velocity_x: 0.0_f32,
29309 angular_velocity_y: 0.0_f32,
29310 angular_velocity_z: 0.0_f32,
29311 failure_flags: GimbalDeviceErrorFlags::DEFAULT,
29312 flags: GimbalDeviceFlags::DEFAULT,
29313 target_system: 0_u8,
29314 target_component: 0_u8,
29315 delta_yaw: 0.0_f32,
29316 delta_yaw_velocity: 0.0_f32,
29317 gimbal_device_id: 0_u8,
29318 };
29319 #[cfg(feature = "arbitrary")]
29320 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29321 use arbitrary::{Arbitrary, Unstructured};
29322 let mut buf = [0u8; 1024];
29323 rng.fill_bytes(&mut buf);
29324 let mut unstructured = Unstructured::new(&buf);
29325 Self::arbitrary(&mut unstructured).unwrap_or_default()
29326 }
29327}
29328impl Default for GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
29329 fn default() -> Self {
29330 Self::DEFAULT.clone()
29331 }
29332}
29333impl MessageData for GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
29334 type Message = MavMessage;
29335 const ID: u32 = 285u32;
29336 const NAME: &'static str = "GIMBAL_DEVICE_ATTITUDE_STATUS";
29337 const EXTRA_CRC: u8 = 137u8;
29338 const ENCODED_LEN: usize = 49usize;
29339 fn deser(
29340 _version: MavlinkVersion,
29341 __input: &[u8],
29342 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29343 let avail_len = __input.len();
29344 let mut payload_buf = [0; Self::ENCODED_LEN];
29345 let mut buf = if avail_len < Self::ENCODED_LEN {
29346 payload_buf[0..avail_len].copy_from_slice(__input);
29347 Bytes::new(&payload_buf)
29348 } else {
29349 Bytes::new(__input)
29350 };
29351 let mut __struct = Self::default();
29352 __struct.time_boot_ms = buf.get_u32_le();
29353 for v in &mut __struct.q {
29354 let val = buf.get_f32_le();
29355 *v = val;
29356 }
29357 __struct.angular_velocity_x = buf.get_f32_le();
29358 __struct.angular_velocity_y = buf.get_f32_le();
29359 __struct.angular_velocity_z = buf.get_f32_le();
29360 let tmp = buf.get_u32_le();
29361 __struct.failure_flags = GimbalDeviceErrorFlags::from_bits(
29362 tmp & GimbalDeviceErrorFlags::all().bits(),
29363 )
29364 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
29365 flag_type: "GimbalDeviceErrorFlags",
29366 value: tmp as u32,
29367 })?;
29368 let tmp = buf.get_u16_le();
29369 __struct.flags = GimbalDeviceFlags::from_bits(tmp & GimbalDeviceFlags::all().bits())
29370 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
29371 flag_type: "GimbalDeviceFlags",
29372 value: tmp as u32,
29373 })?;
29374 __struct.target_system = buf.get_u8();
29375 __struct.target_component = buf.get_u8();
29376 __struct.delta_yaw = buf.get_f32_le();
29377 __struct.delta_yaw_velocity = buf.get_f32_le();
29378 __struct.gimbal_device_id = buf.get_u8();
29379 Ok(__struct)
29380 }
29381 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29382 let mut __tmp = BytesMut::new(bytes);
29383 #[allow(clippy::absurd_extreme_comparisons)]
29384 #[allow(unused_comparisons)]
29385 if __tmp.remaining() < Self::ENCODED_LEN {
29386 panic!(
29387 "buffer is too small (need {} bytes, but got {})",
29388 Self::ENCODED_LEN,
29389 __tmp.remaining(),
29390 )
29391 }
29392 __tmp.put_u32_le(self.time_boot_ms);
29393 for val in &self.q {
29394 __tmp.put_f32_le(*val);
29395 }
29396 __tmp.put_f32_le(self.angular_velocity_x);
29397 __tmp.put_f32_le(self.angular_velocity_y);
29398 __tmp.put_f32_le(self.angular_velocity_z);
29399 __tmp.put_u32_le(self.failure_flags.bits());
29400 __tmp.put_u16_le(self.flags.bits());
29401 __tmp.put_u8(self.target_system);
29402 __tmp.put_u8(self.target_component);
29403 __tmp.put_f32_le(self.delta_yaw);
29404 __tmp.put_f32_le(self.delta_yaw_velocity);
29405 __tmp.put_u8(self.gimbal_device_id);
29406 if matches!(version, MavlinkVersion::V2) {
29407 let len = __tmp.len();
29408 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29409 } else {
29410 __tmp.len()
29411 }
29412 }
29413}
29414#[doc = "id: 33"]
29415#[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient."]
29416#[derive(Debug, Clone, PartialEq)]
29417#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29418#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29419pub struct GLOBAL_POSITION_INT_DATA {
29420 #[doc = "Timestamp (time since system boot)."]
29421 pub time_boot_ms: u32,
29422 #[doc = "Latitude, expressed"]
29423 pub lat: i32,
29424 #[doc = "Longitude, expressed"]
29425 pub lon: i32,
29426 #[doc = "Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL."]
29427 pub alt: i32,
29428 #[doc = "Altitude above home"]
29429 pub relative_alt: i32,
29430 #[doc = "Ground X Speed (Latitude, positive north)"]
29431 pub vx: i16,
29432 #[doc = "Ground Y Speed (Longitude, positive east)"]
29433 pub vy: i16,
29434 #[doc = "Ground Z Speed (Altitude, positive down)"]
29435 pub vz: i16,
29436 #[doc = "Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
29437 pub hdg: u16,
29438}
29439impl GLOBAL_POSITION_INT_DATA {
29440 pub const ENCODED_LEN: usize = 28usize;
29441 pub const DEFAULT: Self = Self {
29442 time_boot_ms: 0_u32,
29443 lat: 0_i32,
29444 lon: 0_i32,
29445 alt: 0_i32,
29446 relative_alt: 0_i32,
29447 vx: 0_i16,
29448 vy: 0_i16,
29449 vz: 0_i16,
29450 hdg: 0_u16,
29451 };
29452 #[cfg(feature = "arbitrary")]
29453 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29454 use arbitrary::{Arbitrary, Unstructured};
29455 let mut buf = [0u8; 1024];
29456 rng.fill_bytes(&mut buf);
29457 let mut unstructured = Unstructured::new(&buf);
29458 Self::arbitrary(&mut unstructured).unwrap_or_default()
29459 }
29460}
29461impl Default for GLOBAL_POSITION_INT_DATA {
29462 fn default() -> Self {
29463 Self::DEFAULT.clone()
29464 }
29465}
29466impl MessageData for GLOBAL_POSITION_INT_DATA {
29467 type Message = MavMessage;
29468 const ID: u32 = 33u32;
29469 const NAME: &'static str = "GLOBAL_POSITION_INT";
29470 const EXTRA_CRC: u8 = 104u8;
29471 const ENCODED_LEN: usize = 28usize;
29472 fn deser(
29473 _version: MavlinkVersion,
29474 __input: &[u8],
29475 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29476 let avail_len = __input.len();
29477 let mut payload_buf = [0; Self::ENCODED_LEN];
29478 let mut buf = if avail_len < Self::ENCODED_LEN {
29479 payload_buf[0..avail_len].copy_from_slice(__input);
29480 Bytes::new(&payload_buf)
29481 } else {
29482 Bytes::new(__input)
29483 };
29484 let mut __struct = Self::default();
29485 __struct.time_boot_ms = buf.get_u32_le();
29486 __struct.lat = buf.get_i32_le();
29487 __struct.lon = buf.get_i32_le();
29488 __struct.alt = buf.get_i32_le();
29489 __struct.relative_alt = buf.get_i32_le();
29490 __struct.vx = buf.get_i16_le();
29491 __struct.vy = buf.get_i16_le();
29492 __struct.vz = buf.get_i16_le();
29493 __struct.hdg = buf.get_u16_le();
29494 Ok(__struct)
29495 }
29496 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29497 let mut __tmp = BytesMut::new(bytes);
29498 #[allow(clippy::absurd_extreme_comparisons)]
29499 #[allow(unused_comparisons)]
29500 if __tmp.remaining() < Self::ENCODED_LEN {
29501 panic!(
29502 "buffer is too small (need {} bytes, but got {})",
29503 Self::ENCODED_LEN,
29504 __tmp.remaining(),
29505 )
29506 }
29507 __tmp.put_u32_le(self.time_boot_ms);
29508 __tmp.put_i32_le(self.lat);
29509 __tmp.put_i32_le(self.lon);
29510 __tmp.put_i32_le(self.alt);
29511 __tmp.put_i32_le(self.relative_alt);
29512 __tmp.put_i16_le(self.vx);
29513 __tmp.put_i16_le(self.vy);
29514 __tmp.put_i16_le(self.vz);
29515 __tmp.put_u16_le(self.hdg);
29516 if matches!(version, MavlinkVersion::V2) {
29517 let len = __tmp.len();
29518 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29519 } else {
29520 __tmp.len()
29521 }
29522 }
29523}
29524#[doc = "id: 101"]
29525#[doc = "Global position/attitude estimate from a vision source."]
29526#[derive(Debug, Clone, PartialEq)]
29527#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29528#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29529pub struct GLOBAL_VISION_POSITION_ESTIMATE_DATA {
29530 #[doc = "Timestamp (UNIX time or since system boot)"]
29531 pub usec: u64,
29532 #[doc = "Global X position"]
29533 pub x: f32,
29534 #[doc = "Global Y position"]
29535 pub y: f32,
29536 #[doc = "Global Z position"]
29537 pub z: f32,
29538 #[doc = "Roll angle"]
29539 pub roll: f32,
29540 #[doc = "Pitch angle"]
29541 pub pitch: f32,
29542 #[doc = "Yaw angle"]
29543 pub yaw: f32,
29544 #[doc = "Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
29545 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29546 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29547 pub covariance: [f32; 21],
29548 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
29549 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29550 pub reset_counter: u8,
29551}
29552impl GLOBAL_VISION_POSITION_ESTIMATE_DATA {
29553 pub const ENCODED_LEN: usize = 117usize;
29554 pub const DEFAULT: Self = Self {
29555 usec: 0_u64,
29556 x: 0.0_f32,
29557 y: 0.0_f32,
29558 z: 0.0_f32,
29559 roll: 0.0_f32,
29560 pitch: 0.0_f32,
29561 yaw: 0.0_f32,
29562 covariance: [0.0_f32; 21usize],
29563 reset_counter: 0_u8,
29564 };
29565 #[cfg(feature = "arbitrary")]
29566 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29567 use arbitrary::{Arbitrary, Unstructured};
29568 let mut buf = [0u8; 1024];
29569 rng.fill_bytes(&mut buf);
29570 let mut unstructured = Unstructured::new(&buf);
29571 Self::arbitrary(&mut unstructured).unwrap_or_default()
29572 }
29573}
29574impl Default for GLOBAL_VISION_POSITION_ESTIMATE_DATA {
29575 fn default() -> Self {
29576 Self::DEFAULT.clone()
29577 }
29578}
29579impl MessageData for GLOBAL_VISION_POSITION_ESTIMATE_DATA {
29580 type Message = MavMessage;
29581 const ID: u32 = 101u32;
29582 const NAME: &'static str = "GLOBAL_VISION_POSITION_ESTIMATE";
29583 const EXTRA_CRC: u8 = 102u8;
29584 const ENCODED_LEN: usize = 117usize;
29585 fn deser(
29586 _version: MavlinkVersion,
29587 __input: &[u8],
29588 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29589 let avail_len = __input.len();
29590 let mut payload_buf = [0; Self::ENCODED_LEN];
29591 let mut buf = if avail_len < Self::ENCODED_LEN {
29592 payload_buf[0..avail_len].copy_from_slice(__input);
29593 Bytes::new(&payload_buf)
29594 } else {
29595 Bytes::new(__input)
29596 };
29597 let mut __struct = Self::default();
29598 __struct.usec = buf.get_u64_le();
29599 __struct.x = buf.get_f32_le();
29600 __struct.y = buf.get_f32_le();
29601 __struct.z = buf.get_f32_le();
29602 __struct.roll = buf.get_f32_le();
29603 __struct.pitch = buf.get_f32_le();
29604 __struct.yaw = buf.get_f32_le();
29605 for v in &mut __struct.covariance {
29606 let val = buf.get_f32_le();
29607 *v = val;
29608 }
29609 __struct.reset_counter = buf.get_u8();
29610 Ok(__struct)
29611 }
29612 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29613 let mut __tmp = BytesMut::new(bytes);
29614 #[allow(clippy::absurd_extreme_comparisons)]
29615 #[allow(unused_comparisons)]
29616 if __tmp.remaining() < Self::ENCODED_LEN {
29617 panic!(
29618 "buffer is too small (need {} bytes, but got {})",
29619 Self::ENCODED_LEN,
29620 __tmp.remaining(),
29621 )
29622 }
29623 __tmp.put_u64_le(self.usec);
29624 __tmp.put_f32_le(self.x);
29625 __tmp.put_f32_le(self.y);
29626 __tmp.put_f32_le(self.z);
29627 __tmp.put_f32_le(self.roll);
29628 __tmp.put_f32_le(self.pitch);
29629 __tmp.put_f32_le(self.yaw);
29630 for val in &self.covariance {
29631 __tmp.put_f32_le(*val);
29632 }
29633 __tmp.put_u8(self.reset_counter);
29634 if matches!(version, MavlinkVersion::V2) {
29635 let len = __tmp.len();
29636 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29637 } else {
29638 __tmp.len()
29639 }
29640 }
29641}
29642#[doc = "id: 385"]
29643#[doc = "Message for transporting \"arbitrary\" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification."]
29644#[derive(Debug, Clone, PartialEq)]
29645#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29646#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29647pub struct TUNNEL_DATA {
29648 #[doc = "A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase."]
29649 pub payload_type: MavTunnelPayloadType,
29650 #[doc = "System ID (can be 0 for broadcast, but this is discouraged)"]
29651 pub target_system: u8,
29652 #[doc = "Component ID (can be 0 for broadcast, but this is discouraged)"]
29653 pub target_component: u8,
29654 #[doc = "Length of the data transported in payload"]
29655 pub payload_length: u8,
29656 #[doc = "Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type."]
29657 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29658 pub payload: [u8; 128],
29659}
29660impl TUNNEL_DATA {
29661 pub const ENCODED_LEN: usize = 133usize;
29662 pub const DEFAULT: Self = Self {
29663 payload_type: MavTunnelPayloadType::DEFAULT,
29664 target_system: 0_u8,
29665 target_component: 0_u8,
29666 payload_length: 0_u8,
29667 payload: [0_u8; 128usize],
29668 };
29669 #[cfg(feature = "arbitrary")]
29670 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29671 use arbitrary::{Arbitrary, Unstructured};
29672 let mut buf = [0u8; 1024];
29673 rng.fill_bytes(&mut buf);
29674 let mut unstructured = Unstructured::new(&buf);
29675 Self::arbitrary(&mut unstructured).unwrap_or_default()
29676 }
29677}
29678impl Default for TUNNEL_DATA {
29679 fn default() -> Self {
29680 Self::DEFAULT.clone()
29681 }
29682}
29683impl MessageData for TUNNEL_DATA {
29684 type Message = MavMessage;
29685 const ID: u32 = 385u32;
29686 const NAME: &'static str = "TUNNEL";
29687 const EXTRA_CRC: u8 = 147u8;
29688 const ENCODED_LEN: usize = 133usize;
29689 fn deser(
29690 _version: MavlinkVersion,
29691 __input: &[u8],
29692 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29693 let avail_len = __input.len();
29694 let mut payload_buf = [0; Self::ENCODED_LEN];
29695 let mut buf = if avail_len < Self::ENCODED_LEN {
29696 payload_buf[0..avail_len].copy_from_slice(__input);
29697 Bytes::new(&payload_buf)
29698 } else {
29699 Bytes::new(__input)
29700 };
29701 let mut __struct = Self::default();
29702 let tmp = buf.get_u16_le();
29703 __struct.payload_type = FromPrimitive::from_u16(tmp).ok_or(
29704 ::mavlink_core::error::ParserError::InvalidEnum {
29705 enum_type: "MavTunnelPayloadType",
29706 value: tmp as u32,
29707 },
29708 )?;
29709 __struct.target_system = buf.get_u8();
29710 __struct.target_component = buf.get_u8();
29711 __struct.payload_length = buf.get_u8();
29712 for v in &mut __struct.payload {
29713 let val = buf.get_u8();
29714 *v = val;
29715 }
29716 Ok(__struct)
29717 }
29718 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29719 let mut __tmp = BytesMut::new(bytes);
29720 #[allow(clippy::absurd_extreme_comparisons)]
29721 #[allow(unused_comparisons)]
29722 if __tmp.remaining() < Self::ENCODED_LEN {
29723 panic!(
29724 "buffer is too small (need {} bytes, but got {})",
29725 Self::ENCODED_LEN,
29726 __tmp.remaining(),
29727 )
29728 }
29729 __tmp.put_u16_le(self.payload_type as u16);
29730 __tmp.put_u8(self.target_system);
29731 __tmp.put_u8(self.target_component);
29732 __tmp.put_u8(self.payload_length);
29733 for val in &self.payload {
29734 __tmp.put_u8(*val);
29735 }
29736 if matches!(version, MavlinkVersion::V2) {
29737 let len = __tmp.len();
29738 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29739 } else {
29740 __tmp.len()
29741 }
29742 }
29743}
29744#[doc = "id: 322"]
29745#[doc = "Emit the value of a parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows them to re-request missing parameters after a loss or timeout."]
29746#[derive(Debug, Clone, PartialEq)]
29747#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29748#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29749pub struct PARAM_EXT_VALUE_DATA {
29750 #[doc = "Total number of parameters"]
29751 pub param_count: u16,
29752 #[doc = "Index of this parameter"]
29753 pub param_index: u16,
29754 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
29755 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29756 pub param_id: [u8; 16],
29757 #[doc = "Parameter value"]
29758 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29759 pub param_value: [u8; 128],
29760 #[doc = "Parameter type."]
29761 pub param_type: MavParamExtType,
29762}
29763impl PARAM_EXT_VALUE_DATA {
29764 pub const ENCODED_LEN: usize = 149usize;
29765 pub const DEFAULT: Self = Self {
29766 param_count: 0_u16,
29767 param_index: 0_u16,
29768 param_id: [0_u8; 16usize],
29769 param_value: [0_u8; 128usize],
29770 param_type: MavParamExtType::DEFAULT,
29771 };
29772 #[cfg(feature = "arbitrary")]
29773 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29774 use arbitrary::{Arbitrary, Unstructured};
29775 let mut buf = [0u8; 1024];
29776 rng.fill_bytes(&mut buf);
29777 let mut unstructured = Unstructured::new(&buf);
29778 Self::arbitrary(&mut unstructured).unwrap_or_default()
29779 }
29780}
29781impl Default for PARAM_EXT_VALUE_DATA {
29782 fn default() -> Self {
29783 Self::DEFAULT.clone()
29784 }
29785}
29786impl MessageData for PARAM_EXT_VALUE_DATA {
29787 type Message = MavMessage;
29788 const ID: u32 = 322u32;
29789 const NAME: &'static str = "PARAM_EXT_VALUE";
29790 const EXTRA_CRC: u8 = 243u8;
29791 const ENCODED_LEN: usize = 149usize;
29792 fn deser(
29793 _version: MavlinkVersion,
29794 __input: &[u8],
29795 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29796 let avail_len = __input.len();
29797 let mut payload_buf = [0; Self::ENCODED_LEN];
29798 let mut buf = if avail_len < Self::ENCODED_LEN {
29799 payload_buf[0..avail_len].copy_from_slice(__input);
29800 Bytes::new(&payload_buf)
29801 } else {
29802 Bytes::new(__input)
29803 };
29804 let mut __struct = Self::default();
29805 __struct.param_count = buf.get_u16_le();
29806 __struct.param_index = buf.get_u16_le();
29807 for v in &mut __struct.param_id {
29808 let val = buf.get_u8();
29809 *v = val;
29810 }
29811 for v in &mut __struct.param_value {
29812 let val = buf.get_u8();
29813 *v = val;
29814 }
29815 let tmp = buf.get_u8();
29816 __struct.param_type =
29817 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29818 enum_type: "MavParamExtType",
29819 value: tmp as u32,
29820 })?;
29821 Ok(__struct)
29822 }
29823 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29824 let mut __tmp = BytesMut::new(bytes);
29825 #[allow(clippy::absurd_extreme_comparisons)]
29826 #[allow(unused_comparisons)]
29827 if __tmp.remaining() < Self::ENCODED_LEN {
29828 panic!(
29829 "buffer is too small (need {} bytes, but got {})",
29830 Self::ENCODED_LEN,
29831 __tmp.remaining(),
29832 )
29833 }
29834 __tmp.put_u16_le(self.param_count);
29835 __tmp.put_u16_le(self.param_index);
29836 for val in &self.param_id {
29837 __tmp.put_u8(*val);
29838 }
29839 for val in &self.param_value {
29840 __tmp.put_u8(*val);
29841 }
29842 __tmp.put_u8(self.param_type as u8);
29843 if matches!(version, MavlinkVersion::V2) {
29844 let len = __tmp.len();
29845 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29846 } else {
29847 __tmp.len()
29848 }
29849 }
29850}
29851#[doc = "id: 135"]
29852#[doc = "Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission."]
29853#[derive(Debug, Clone, PartialEq)]
29854#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29855#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29856pub struct TERRAIN_CHECK_DATA {
29857 #[doc = "Latitude"]
29858 pub lat: i32,
29859 #[doc = "Longitude"]
29860 pub lon: i32,
29861}
29862impl TERRAIN_CHECK_DATA {
29863 pub const ENCODED_LEN: usize = 8usize;
29864 pub const DEFAULT: Self = Self {
29865 lat: 0_i32,
29866 lon: 0_i32,
29867 };
29868 #[cfg(feature = "arbitrary")]
29869 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29870 use arbitrary::{Arbitrary, Unstructured};
29871 let mut buf = [0u8; 1024];
29872 rng.fill_bytes(&mut buf);
29873 let mut unstructured = Unstructured::new(&buf);
29874 Self::arbitrary(&mut unstructured).unwrap_or_default()
29875 }
29876}
29877impl Default for TERRAIN_CHECK_DATA {
29878 fn default() -> Self {
29879 Self::DEFAULT.clone()
29880 }
29881}
29882impl MessageData for TERRAIN_CHECK_DATA {
29883 type Message = MavMessage;
29884 const ID: u32 = 135u32;
29885 const NAME: &'static str = "TERRAIN_CHECK";
29886 const EXTRA_CRC: u8 = 203u8;
29887 const ENCODED_LEN: usize = 8usize;
29888 fn deser(
29889 _version: MavlinkVersion,
29890 __input: &[u8],
29891 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29892 let avail_len = __input.len();
29893 let mut payload_buf = [0; Self::ENCODED_LEN];
29894 let mut buf = if avail_len < Self::ENCODED_LEN {
29895 payload_buf[0..avail_len].copy_from_slice(__input);
29896 Bytes::new(&payload_buf)
29897 } else {
29898 Bytes::new(__input)
29899 };
29900 let mut __struct = Self::default();
29901 __struct.lat = buf.get_i32_le();
29902 __struct.lon = buf.get_i32_le();
29903 Ok(__struct)
29904 }
29905 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29906 let mut __tmp = BytesMut::new(bytes);
29907 #[allow(clippy::absurd_extreme_comparisons)]
29908 #[allow(unused_comparisons)]
29909 if __tmp.remaining() < Self::ENCODED_LEN {
29910 panic!(
29911 "buffer is too small (need {} bytes, but got {})",
29912 Self::ENCODED_LEN,
29913 __tmp.remaining(),
29914 )
29915 }
29916 __tmp.put_i32_le(self.lat);
29917 __tmp.put_i32_le(self.lon);
29918 if matches!(version, MavlinkVersion::V2) {
29919 let len = __tmp.len();
29920 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29921 } else {
29922 __tmp.len()
29923 }
29924 }
29925}
29926#[doc = "id: 77"]
29927#[doc = "Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
29928#[derive(Debug, Clone, PartialEq)]
29929#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29930#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29931pub struct COMMAND_ACK_DATA {
29932 #[doc = "Command ID (of acknowledged command)."]
29933 pub command: MavCmd,
29934 #[doc = "Result of command."]
29935 pub result: MavResult,
29936 #[doc = "The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown."]
29937 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29938 pub progress: u8,
29939 #[doc = "Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate \"unused\" or \"unknown\")."]
29940 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29941 pub result_param2: i32,
29942 #[doc = "System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement."]
29943 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29944 pub target_system: u8,
29945 #[doc = "Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement."]
29946 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29947 pub target_component: u8,
29948}
29949impl COMMAND_ACK_DATA {
29950 pub const ENCODED_LEN: usize = 10usize;
29951 pub const DEFAULT: Self = Self {
29952 command: MavCmd::DEFAULT,
29953 result: MavResult::DEFAULT,
29954 progress: 0_u8,
29955 result_param2: 0_i32,
29956 target_system: 0_u8,
29957 target_component: 0_u8,
29958 };
29959 #[cfg(feature = "arbitrary")]
29960 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29961 use arbitrary::{Arbitrary, Unstructured};
29962 let mut buf = [0u8; 1024];
29963 rng.fill_bytes(&mut buf);
29964 let mut unstructured = Unstructured::new(&buf);
29965 Self::arbitrary(&mut unstructured).unwrap_or_default()
29966 }
29967}
29968impl Default for COMMAND_ACK_DATA {
29969 fn default() -> Self {
29970 Self::DEFAULT.clone()
29971 }
29972}
29973impl MessageData for COMMAND_ACK_DATA {
29974 type Message = MavMessage;
29975 const ID: u32 = 77u32;
29976 const NAME: &'static str = "COMMAND_ACK";
29977 const EXTRA_CRC: u8 = 143u8;
29978 const ENCODED_LEN: usize = 10usize;
29979 fn deser(
29980 _version: MavlinkVersion,
29981 __input: &[u8],
29982 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29983 let avail_len = __input.len();
29984 let mut payload_buf = [0; Self::ENCODED_LEN];
29985 let mut buf = if avail_len < Self::ENCODED_LEN {
29986 payload_buf[0..avail_len].copy_from_slice(__input);
29987 Bytes::new(&payload_buf)
29988 } else {
29989 Bytes::new(__input)
29990 };
29991 let mut __struct = Self::default();
29992 let tmp = buf.get_u16_le();
29993 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
29994 ::mavlink_core::error::ParserError::InvalidEnum {
29995 enum_type: "MavCmd",
29996 value: tmp as u32,
29997 },
29998 )?;
29999 let tmp = buf.get_u8();
30000 __struct.result =
30001 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30002 enum_type: "MavResult",
30003 value: tmp as u32,
30004 })?;
30005 __struct.progress = buf.get_u8();
30006 __struct.result_param2 = buf.get_i32_le();
30007 __struct.target_system = buf.get_u8();
30008 __struct.target_component = buf.get_u8();
30009 Ok(__struct)
30010 }
30011 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30012 let mut __tmp = BytesMut::new(bytes);
30013 #[allow(clippy::absurd_extreme_comparisons)]
30014 #[allow(unused_comparisons)]
30015 if __tmp.remaining() < Self::ENCODED_LEN {
30016 panic!(
30017 "buffer is too small (need {} bytes, but got {})",
30018 Self::ENCODED_LEN,
30019 __tmp.remaining(),
30020 )
30021 }
30022 __tmp.put_u16_le(self.command as u16);
30023 __tmp.put_u8(self.result as u8);
30024 __tmp.put_u8(self.progress);
30025 __tmp.put_i32_le(self.result_param2);
30026 __tmp.put_u8(self.target_system);
30027 __tmp.put_u8(self.target_component);
30028 if matches!(version, MavlinkVersion::V2) {
30029 let len = __tmp.len();
30030 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30031 } else {
30032 __tmp.len()
30033 }
30034 }
30035}
30036#[doc = "id: 39"]
30037#[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system's current latitude or yaw rather than a specific value). See also <https://mavlink.io/en/services/mission.html>."]
30038#[derive(Debug, Clone, PartialEq)]
30039#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30040#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30041pub struct MISSION_ITEM_DATA {
30042 #[doc = "PARAM1, see MAV_CMD enum"]
30043 pub param1: f32,
30044 #[doc = "PARAM2, see MAV_CMD enum"]
30045 pub param2: f32,
30046 #[doc = "PARAM3, see MAV_CMD enum"]
30047 pub param3: f32,
30048 #[doc = "PARAM4, see MAV_CMD enum"]
30049 pub param4: f32,
30050 #[doc = "PARAM5 / local: X coordinate, global: latitude"]
30051 pub x: f32,
30052 #[doc = "PARAM6 / local: Y coordinate, global: longitude"]
30053 pub y: f32,
30054 #[doc = "PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame)."]
30055 pub z: f32,
30056 #[doc = "Sequence"]
30057 pub seq: u16,
30058 #[doc = "The scheduled action for the waypoint."]
30059 pub command: MavCmd,
30060 #[doc = "System ID"]
30061 pub target_system: u8,
30062 #[doc = "Component ID"]
30063 pub target_component: u8,
30064 #[doc = "The coordinate system of the waypoint."]
30065 pub frame: MavFrame,
30066 #[doc = "false:0, true:1"]
30067 pub current: u8,
30068 #[doc = "Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes."]
30069 pub autocontinue: u8,
30070 #[doc = "Mission type."]
30071 #[cfg_attr(feature = "serde", serde(default))]
30072 pub mission_type: MavMissionType,
30073}
30074impl MISSION_ITEM_DATA {
30075 pub const ENCODED_LEN: usize = 38usize;
30076 pub const DEFAULT: Self = Self {
30077 param1: 0.0_f32,
30078 param2: 0.0_f32,
30079 param3: 0.0_f32,
30080 param4: 0.0_f32,
30081 x: 0.0_f32,
30082 y: 0.0_f32,
30083 z: 0.0_f32,
30084 seq: 0_u16,
30085 command: MavCmd::DEFAULT,
30086 target_system: 0_u8,
30087 target_component: 0_u8,
30088 frame: MavFrame::DEFAULT,
30089 current: 0_u8,
30090 autocontinue: 0_u8,
30091 mission_type: MavMissionType::DEFAULT,
30092 };
30093 #[cfg(feature = "arbitrary")]
30094 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30095 use arbitrary::{Arbitrary, Unstructured};
30096 let mut buf = [0u8; 1024];
30097 rng.fill_bytes(&mut buf);
30098 let mut unstructured = Unstructured::new(&buf);
30099 Self::arbitrary(&mut unstructured).unwrap_or_default()
30100 }
30101}
30102impl Default for MISSION_ITEM_DATA {
30103 fn default() -> Self {
30104 Self::DEFAULT.clone()
30105 }
30106}
30107impl MessageData for MISSION_ITEM_DATA {
30108 type Message = MavMessage;
30109 const ID: u32 = 39u32;
30110 const NAME: &'static str = "MISSION_ITEM";
30111 const EXTRA_CRC: u8 = 254u8;
30112 const ENCODED_LEN: usize = 38usize;
30113 fn deser(
30114 _version: MavlinkVersion,
30115 __input: &[u8],
30116 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30117 let avail_len = __input.len();
30118 let mut payload_buf = [0; Self::ENCODED_LEN];
30119 let mut buf = if avail_len < Self::ENCODED_LEN {
30120 payload_buf[0..avail_len].copy_from_slice(__input);
30121 Bytes::new(&payload_buf)
30122 } else {
30123 Bytes::new(__input)
30124 };
30125 let mut __struct = Self::default();
30126 __struct.param1 = buf.get_f32_le();
30127 __struct.param2 = buf.get_f32_le();
30128 __struct.param3 = buf.get_f32_le();
30129 __struct.param4 = buf.get_f32_le();
30130 __struct.x = buf.get_f32_le();
30131 __struct.y = buf.get_f32_le();
30132 __struct.z = buf.get_f32_le();
30133 __struct.seq = buf.get_u16_le();
30134 let tmp = buf.get_u16_le();
30135 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
30136 ::mavlink_core::error::ParserError::InvalidEnum {
30137 enum_type: "MavCmd",
30138 value: tmp as u32,
30139 },
30140 )?;
30141 __struct.target_system = buf.get_u8();
30142 __struct.target_component = buf.get_u8();
30143 let tmp = buf.get_u8();
30144 __struct.frame =
30145 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30146 enum_type: "MavFrame",
30147 value: tmp as u32,
30148 })?;
30149 __struct.current = buf.get_u8();
30150 __struct.autocontinue = buf.get_u8();
30151 let tmp = buf.get_u8();
30152 __struct.mission_type =
30153 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30154 enum_type: "MavMissionType",
30155 value: tmp as u32,
30156 })?;
30157 Ok(__struct)
30158 }
30159 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30160 let mut __tmp = BytesMut::new(bytes);
30161 #[allow(clippy::absurd_extreme_comparisons)]
30162 #[allow(unused_comparisons)]
30163 if __tmp.remaining() < Self::ENCODED_LEN {
30164 panic!(
30165 "buffer is too small (need {} bytes, but got {})",
30166 Self::ENCODED_LEN,
30167 __tmp.remaining(),
30168 )
30169 }
30170 __tmp.put_f32_le(self.param1);
30171 __tmp.put_f32_le(self.param2);
30172 __tmp.put_f32_le(self.param3);
30173 __tmp.put_f32_le(self.param4);
30174 __tmp.put_f32_le(self.x);
30175 __tmp.put_f32_le(self.y);
30176 __tmp.put_f32_le(self.z);
30177 __tmp.put_u16_le(self.seq);
30178 __tmp.put_u16_le(self.command as u16);
30179 __tmp.put_u8(self.target_system);
30180 __tmp.put_u8(self.target_component);
30181 __tmp.put_u8(self.frame as u8);
30182 __tmp.put_u8(self.current);
30183 __tmp.put_u8(self.autocontinue);
30184 __tmp.put_u8(self.mission_type as u8);
30185 if matches!(version, MavlinkVersion::V2) {
30186 let len = __tmp.len();
30187 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30188 } else {
30189 __tmp.len()
30190 }
30191 }
30192}
30193#[doc = "id: 332"]
30194#[doc = "Describe a trajectory using an array of up-to 5 waypoints in the local frame (MAV_FRAME_LOCAL_NED)."]
30195#[derive(Debug, Clone, PartialEq)]
30196#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30197#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30198pub struct TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
30199 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
30200 pub time_usec: u64,
30201 #[doc = "X-coordinate of waypoint, set to NaN if not being used"]
30202 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30203 pub pos_x: [f32; 5],
30204 #[doc = "Y-coordinate of waypoint, set to NaN if not being used"]
30205 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30206 pub pos_y: [f32; 5],
30207 #[doc = "Z-coordinate of waypoint, set to NaN if not being used"]
30208 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30209 pub pos_z: [f32; 5],
30210 #[doc = "X-velocity of waypoint, set to NaN if not being used"]
30211 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30212 pub vel_x: [f32; 5],
30213 #[doc = "Y-velocity of waypoint, set to NaN if not being used"]
30214 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30215 pub vel_y: [f32; 5],
30216 #[doc = "Z-velocity of waypoint, set to NaN if not being used"]
30217 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30218 pub vel_z: [f32; 5],
30219 #[doc = "X-acceleration of waypoint, set to NaN if not being used"]
30220 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30221 pub acc_x: [f32; 5],
30222 #[doc = "Y-acceleration of waypoint, set to NaN if not being used"]
30223 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30224 pub acc_y: [f32; 5],
30225 #[doc = "Z-acceleration of waypoint, set to NaN if not being used"]
30226 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30227 pub acc_z: [f32; 5],
30228 #[doc = "Yaw angle, set to NaN if not being used"]
30229 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30230 pub pos_yaw: [f32; 5],
30231 #[doc = "Yaw rate, set to NaN if not being used"]
30232 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30233 pub vel_yaw: [f32; 5],
30234 #[doc = "MAV_CMD command id of waypoint, set to UINT16_MAX if not being used."]
30235 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30236 pub command: [u16; 5],
30237 #[doc = "Number of valid points (up-to 5 waypoints are possible)"]
30238 pub valid_points: u8,
30239}
30240impl TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
30241 pub const ENCODED_LEN: usize = 239usize;
30242 pub const DEFAULT: Self = Self {
30243 time_usec: 0_u64,
30244 pos_x: [0.0_f32; 5usize],
30245 pos_y: [0.0_f32; 5usize],
30246 pos_z: [0.0_f32; 5usize],
30247 vel_x: [0.0_f32; 5usize],
30248 vel_y: [0.0_f32; 5usize],
30249 vel_z: [0.0_f32; 5usize],
30250 acc_x: [0.0_f32; 5usize],
30251 acc_y: [0.0_f32; 5usize],
30252 acc_z: [0.0_f32; 5usize],
30253 pos_yaw: [0.0_f32; 5usize],
30254 vel_yaw: [0.0_f32; 5usize],
30255 command: [0_u16; 5usize],
30256 valid_points: 0_u8,
30257 };
30258 #[cfg(feature = "arbitrary")]
30259 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30260 use arbitrary::{Arbitrary, Unstructured};
30261 let mut buf = [0u8; 1024];
30262 rng.fill_bytes(&mut buf);
30263 let mut unstructured = Unstructured::new(&buf);
30264 Self::arbitrary(&mut unstructured).unwrap_or_default()
30265 }
30266}
30267impl Default for TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
30268 fn default() -> Self {
30269 Self::DEFAULT.clone()
30270 }
30271}
30272impl MessageData for TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
30273 type Message = MavMessage;
30274 const ID: u32 = 332u32;
30275 const NAME: &'static str = "TRAJECTORY_REPRESENTATION_WAYPOINTS";
30276 const EXTRA_CRC: u8 = 236u8;
30277 const ENCODED_LEN: usize = 239usize;
30278 fn deser(
30279 _version: MavlinkVersion,
30280 __input: &[u8],
30281 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30282 let avail_len = __input.len();
30283 let mut payload_buf = [0; Self::ENCODED_LEN];
30284 let mut buf = if avail_len < Self::ENCODED_LEN {
30285 payload_buf[0..avail_len].copy_from_slice(__input);
30286 Bytes::new(&payload_buf)
30287 } else {
30288 Bytes::new(__input)
30289 };
30290 let mut __struct = Self::default();
30291 __struct.time_usec = buf.get_u64_le();
30292 for v in &mut __struct.pos_x {
30293 let val = buf.get_f32_le();
30294 *v = val;
30295 }
30296 for v in &mut __struct.pos_y {
30297 let val = buf.get_f32_le();
30298 *v = val;
30299 }
30300 for v in &mut __struct.pos_z {
30301 let val = buf.get_f32_le();
30302 *v = val;
30303 }
30304 for v in &mut __struct.vel_x {
30305 let val = buf.get_f32_le();
30306 *v = val;
30307 }
30308 for v in &mut __struct.vel_y {
30309 let val = buf.get_f32_le();
30310 *v = val;
30311 }
30312 for v in &mut __struct.vel_z {
30313 let val = buf.get_f32_le();
30314 *v = val;
30315 }
30316 for v in &mut __struct.acc_x {
30317 let val = buf.get_f32_le();
30318 *v = val;
30319 }
30320 for v in &mut __struct.acc_y {
30321 let val = buf.get_f32_le();
30322 *v = val;
30323 }
30324 for v in &mut __struct.acc_z {
30325 let val = buf.get_f32_le();
30326 *v = val;
30327 }
30328 for v in &mut __struct.pos_yaw {
30329 let val = buf.get_f32_le();
30330 *v = val;
30331 }
30332 for v in &mut __struct.vel_yaw {
30333 let val = buf.get_f32_le();
30334 *v = val;
30335 }
30336 for v in &mut __struct.command {
30337 let val = buf.get_u16_le();
30338 *v = val;
30339 }
30340 __struct.valid_points = buf.get_u8();
30341 Ok(__struct)
30342 }
30343 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30344 let mut __tmp = BytesMut::new(bytes);
30345 #[allow(clippy::absurd_extreme_comparisons)]
30346 #[allow(unused_comparisons)]
30347 if __tmp.remaining() < Self::ENCODED_LEN {
30348 panic!(
30349 "buffer is too small (need {} bytes, but got {})",
30350 Self::ENCODED_LEN,
30351 __tmp.remaining(),
30352 )
30353 }
30354 __tmp.put_u64_le(self.time_usec);
30355 for val in &self.pos_x {
30356 __tmp.put_f32_le(*val);
30357 }
30358 for val in &self.pos_y {
30359 __tmp.put_f32_le(*val);
30360 }
30361 for val in &self.pos_z {
30362 __tmp.put_f32_le(*val);
30363 }
30364 for val in &self.vel_x {
30365 __tmp.put_f32_le(*val);
30366 }
30367 for val in &self.vel_y {
30368 __tmp.put_f32_le(*val);
30369 }
30370 for val in &self.vel_z {
30371 __tmp.put_f32_le(*val);
30372 }
30373 for val in &self.acc_x {
30374 __tmp.put_f32_le(*val);
30375 }
30376 for val in &self.acc_y {
30377 __tmp.put_f32_le(*val);
30378 }
30379 for val in &self.acc_z {
30380 __tmp.put_f32_le(*val);
30381 }
30382 for val in &self.pos_yaw {
30383 __tmp.put_f32_le(*val);
30384 }
30385 for val in &self.vel_yaw {
30386 __tmp.put_f32_le(*val);
30387 }
30388 for val in &self.command {
30389 __tmp.put_u16_le(*val);
30390 }
30391 __tmp.put_u8(self.valid_points);
30392 if matches!(version, MavlinkVersion::V2) {
30393 let len = __tmp.len();
30394 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30395 } else {
30396 __tmp.len()
30397 }
30398 }
30399}
30400#[doc = "id: 254"]
30401#[doc = "Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N."]
30402#[derive(Debug, Clone, PartialEq)]
30403#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30404#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30405pub struct DEBUG_DATA {
30406 #[doc = "Timestamp (time since system boot)."]
30407 pub time_boot_ms: u32,
30408 #[doc = "DEBUG value"]
30409 pub value: f32,
30410 #[doc = "index of debug variable"]
30411 pub ind: u8,
30412}
30413impl DEBUG_DATA {
30414 pub const ENCODED_LEN: usize = 9usize;
30415 pub const DEFAULT: Self = Self {
30416 time_boot_ms: 0_u32,
30417 value: 0.0_f32,
30418 ind: 0_u8,
30419 };
30420 #[cfg(feature = "arbitrary")]
30421 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30422 use arbitrary::{Arbitrary, Unstructured};
30423 let mut buf = [0u8; 1024];
30424 rng.fill_bytes(&mut buf);
30425 let mut unstructured = Unstructured::new(&buf);
30426 Self::arbitrary(&mut unstructured).unwrap_or_default()
30427 }
30428}
30429impl Default for DEBUG_DATA {
30430 fn default() -> Self {
30431 Self::DEFAULT.clone()
30432 }
30433}
30434impl MessageData for DEBUG_DATA {
30435 type Message = MavMessage;
30436 const ID: u32 = 254u32;
30437 const NAME: &'static str = "DEBUG";
30438 const EXTRA_CRC: u8 = 46u8;
30439 const ENCODED_LEN: usize = 9usize;
30440 fn deser(
30441 _version: MavlinkVersion,
30442 __input: &[u8],
30443 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30444 let avail_len = __input.len();
30445 let mut payload_buf = [0; Self::ENCODED_LEN];
30446 let mut buf = if avail_len < Self::ENCODED_LEN {
30447 payload_buf[0..avail_len].copy_from_slice(__input);
30448 Bytes::new(&payload_buf)
30449 } else {
30450 Bytes::new(__input)
30451 };
30452 let mut __struct = Self::default();
30453 __struct.time_boot_ms = buf.get_u32_le();
30454 __struct.value = buf.get_f32_le();
30455 __struct.ind = buf.get_u8();
30456 Ok(__struct)
30457 }
30458 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30459 let mut __tmp = BytesMut::new(bytes);
30460 #[allow(clippy::absurd_extreme_comparisons)]
30461 #[allow(unused_comparisons)]
30462 if __tmp.remaining() < Self::ENCODED_LEN {
30463 panic!(
30464 "buffer is too small (need {} bytes, but got {})",
30465 Self::ENCODED_LEN,
30466 __tmp.remaining(),
30467 )
30468 }
30469 __tmp.put_u32_le(self.time_boot_ms);
30470 __tmp.put_f32_le(self.value);
30471 __tmp.put_u8(self.ind);
30472 if matches!(version, MavlinkVersion::V2) {
30473 let len = __tmp.len();
30474 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30475 } else {
30476 __tmp.len()
30477 }
30478 }
30479}
30480#[doc = "id: 124"]
30481#[doc = "Second GPS data."]
30482#[derive(Debug, Clone, PartialEq)]
30483#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30484#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30485pub struct GPS2_RAW_DATA {
30486 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
30487 pub time_usec: u64,
30488 #[doc = "Latitude (WGS84)"]
30489 pub lat: i32,
30490 #[doc = "Longitude (WGS84)"]
30491 pub lon: i32,
30492 #[doc = "Altitude (MSL). Positive for up."]
30493 pub alt: i32,
30494 #[doc = "Age of DGPS info"]
30495 pub dgps_age: u32,
30496 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
30497 pub eph: u16,
30498 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
30499 pub epv: u16,
30500 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
30501 pub vel: u16,
30502 #[doc = "Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
30503 pub cog: u16,
30504 #[doc = "GPS fix type."]
30505 pub fix_type: GpsFixType,
30506 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
30507 pub satellites_visible: u8,
30508 #[doc = "Number of DGPS satellites"]
30509 pub dgps_numch: u8,
30510 #[doc = "Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north."]
30511 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30512 pub yaw: u16,
30513 #[doc = "Altitude (above WGS84, EGM96 ellipsoid). Positive for up."]
30514 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30515 pub alt_ellipsoid: i32,
30516 #[doc = "Position uncertainty."]
30517 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30518 pub h_acc: u32,
30519 #[doc = "Altitude uncertainty."]
30520 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30521 pub v_acc: u32,
30522 #[doc = "Speed uncertainty."]
30523 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30524 pub vel_acc: u32,
30525 #[doc = "Heading / track uncertainty"]
30526 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30527 pub hdg_acc: u32,
30528}
30529impl GPS2_RAW_DATA {
30530 pub const ENCODED_LEN: usize = 57usize;
30531 pub const DEFAULT: Self = Self {
30532 time_usec: 0_u64,
30533 lat: 0_i32,
30534 lon: 0_i32,
30535 alt: 0_i32,
30536 dgps_age: 0_u32,
30537 eph: 0_u16,
30538 epv: 0_u16,
30539 vel: 0_u16,
30540 cog: 0_u16,
30541 fix_type: GpsFixType::DEFAULT,
30542 satellites_visible: 0_u8,
30543 dgps_numch: 0_u8,
30544 yaw: 0_u16,
30545 alt_ellipsoid: 0_i32,
30546 h_acc: 0_u32,
30547 v_acc: 0_u32,
30548 vel_acc: 0_u32,
30549 hdg_acc: 0_u32,
30550 };
30551 #[cfg(feature = "arbitrary")]
30552 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30553 use arbitrary::{Arbitrary, Unstructured};
30554 let mut buf = [0u8; 1024];
30555 rng.fill_bytes(&mut buf);
30556 let mut unstructured = Unstructured::new(&buf);
30557 Self::arbitrary(&mut unstructured).unwrap_or_default()
30558 }
30559}
30560impl Default for GPS2_RAW_DATA {
30561 fn default() -> Self {
30562 Self::DEFAULT.clone()
30563 }
30564}
30565impl MessageData for GPS2_RAW_DATA {
30566 type Message = MavMessage;
30567 const ID: u32 = 124u32;
30568 const NAME: &'static str = "GPS2_RAW";
30569 const EXTRA_CRC: u8 = 87u8;
30570 const ENCODED_LEN: usize = 57usize;
30571 fn deser(
30572 _version: MavlinkVersion,
30573 __input: &[u8],
30574 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30575 let avail_len = __input.len();
30576 let mut payload_buf = [0; Self::ENCODED_LEN];
30577 let mut buf = if avail_len < Self::ENCODED_LEN {
30578 payload_buf[0..avail_len].copy_from_slice(__input);
30579 Bytes::new(&payload_buf)
30580 } else {
30581 Bytes::new(__input)
30582 };
30583 let mut __struct = Self::default();
30584 __struct.time_usec = buf.get_u64_le();
30585 __struct.lat = buf.get_i32_le();
30586 __struct.lon = buf.get_i32_le();
30587 __struct.alt = buf.get_i32_le();
30588 __struct.dgps_age = buf.get_u32_le();
30589 __struct.eph = buf.get_u16_le();
30590 __struct.epv = buf.get_u16_le();
30591 __struct.vel = buf.get_u16_le();
30592 __struct.cog = buf.get_u16_le();
30593 let tmp = buf.get_u8();
30594 __struct.fix_type =
30595 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30596 enum_type: "GpsFixType",
30597 value: tmp as u32,
30598 })?;
30599 __struct.satellites_visible = buf.get_u8();
30600 __struct.dgps_numch = buf.get_u8();
30601 __struct.yaw = buf.get_u16_le();
30602 __struct.alt_ellipsoid = buf.get_i32_le();
30603 __struct.h_acc = buf.get_u32_le();
30604 __struct.v_acc = buf.get_u32_le();
30605 __struct.vel_acc = buf.get_u32_le();
30606 __struct.hdg_acc = buf.get_u32_le();
30607 Ok(__struct)
30608 }
30609 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30610 let mut __tmp = BytesMut::new(bytes);
30611 #[allow(clippy::absurd_extreme_comparisons)]
30612 #[allow(unused_comparisons)]
30613 if __tmp.remaining() < Self::ENCODED_LEN {
30614 panic!(
30615 "buffer is too small (need {} bytes, but got {})",
30616 Self::ENCODED_LEN,
30617 __tmp.remaining(),
30618 )
30619 }
30620 __tmp.put_u64_le(self.time_usec);
30621 __tmp.put_i32_le(self.lat);
30622 __tmp.put_i32_le(self.lon);
30623 __tmp.put_i32_le(self.alt);
30624 __tmp.put_u32_le(self.dgps_age);
30625 __tmp.put_u16_le(self.eph);
30626 __tmp.put_u16_le(self.epv);
30627 __tmp.put_u16_le(self.vel);
30628 __tmp.put_u16_le(self.cog);
30629 __tmp.put_u8(self.fix_type as u8);
30630 __tmp.put_u8(self.satellites_visible);
30631 __tmp.put_u8(self.dgps_numch);
30632 __tmp.put_u16_le(self.yaw);
30633 __tmp.put_i32_le(self.alt_ellipsoid);
30634 __tmp.put_u32_le(self.h_acc);
30635 __tmp.put_u32_le(self.v_acc);
30636 __tmp.put_u32_le(self.vel_acc);
30637 __tmp.put_u32_le(self.hdg_acc);
30638 if matches!(version, MavlinkVersion::V2) {
30639 let len = __tmp.len();
30640 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30641 } else {
30642 __tmp.len()
30643 }
30644 }
30645}
30646#[doc = "id: 390"]
30647#[doc = "Hardware status sent by an onboard computer."]
30648#[derive(Debug, Clone, PartialEq)]
30649#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30650#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30651pub struct ONBOARD_COMPUTER_STATUS_DATA {
30652 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
30653 pub time_usec: u64,
30654 #[doc = "Time since system boot."]
30655 pub uptime: u32,
30656 #[doc = "Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused."]
30657 pub ram_usage: u32,
30658 #[doc = "Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused."]
30659 pub ram_total: u32,
30660 #[doc = "Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused."]
30661 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30662 pub storage_type: [u32; 4],
30663 #[doc = "Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused."]
30664 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30665 pub storage_usage: [u32; 4],
30666 #[doc = "Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused."]
30667 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30668 pub storage_total: [u32; 4],
30669 #[doc = "Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary"]
30670 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30671 pub link_type: [u32; 6],
30672 #[doc = "Network traffic from the component system. A value of UINT32_MAX implies the field is unused."]
30673 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30674 pub link_tx_rate: [u32; 6],
30675 #[doc = "Network traffic to the component system. A value of UINT32_MAX implies the field is unused."]
30676 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30677 pub link_rx_rate: [u32; 6],
30678 #[doc = "Network capacity from the component system. A value of UINT32_MAX implies the field is unused."]
30679 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30680 pub link_tx_max: [u32; 6],
30681 #[doc = "Network capacity to the component system. A value of UINT32_MAX implies the field is unused."]
30682 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30683 pub link_rx_max: [u32; 6],
30684 #[doc = "Fan speeds. A value of INT16_MAX implies the field is unused."]
30685 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30686 pub fan_speed: [i16; 4],
30687 #[doc = "Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers."]
30688 pub mavtype: u8,
30689 #[doc = "CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused."]
30690 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30691 pub cpu_cores: [u8; 8],
30692 #[doc = "Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused."]
30693 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30694 pub cpu_combined: [u8; 10],
30695 #[doc = "GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused."]
30696 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30697 pub gpu_cores: [u8; 4],
30698 #[doc = "Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused."]
30699 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30700 pub gpu_combined: [u8; 10],
30701 #[doc = "Temperature of the board. A value of INT8_MAX implies the field is unused."]
30702 pub temperature_board: i8,
30703 #[doc = "Temperature of the CPU core. A value of INT8_MAX implies the field is unused."]
30704 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30705 pub temperature_core: [i8; 8],
30706}
30707impl ONBOARD_COMPUTER_STATUS_DATA {
30708 pub const ENCODED_LEN: usize = 238usize;
30709 pub const DEFAULT: Self = Self {
30710 time_usec: 0_u64,
30711 uptime: 0_u32,
30712 ram_usage: 0_u32,
30713 ram_total: 0_u32,
30714 storage_type: [0_u32; 4usize],
30715 storage_usage: [0_u32; 4usize],
30716 storage_total: [0_u32; 4usize],
30717 link_type: [0_u32; 6usize],
30718 link_tx_rate: [0_u32; 6usize],
30719 link_rx_rate: [0_u32; 6usize],
30720 link_tx_max: [0_u32; 6usize],
30721 link_rx_max: [0_u32; 6usize],
30722 fan_speed: [0_i16; 4usize],
30723 mavtype: 0_u8,
30724 cpu_cores: [0_u8; 8usize],
30725 cpu_combined: [0_u8; 10usize],
30726 gpu_cores: [0_u8; 4usize],
30727 gpu_combined: [0_u8; 10usize],
30728 temperature_board: 0_i8,
30729 temperature_core: [0_i8; 8usize],
30730 };
30731 #[cfg(feature = "arbitrary")]
30732 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30733 use arbitrary::{Arbitrary, Unstructured};
30734 let mut buf = [0u8; 1024];
30735 rng.fill_bytes(&mut buf);
30736 let mut unstructured = Unstructured::new(&buf);
30737 Self::arbitrary(&mut unstructured).unwrap_or_default()
30738 }
30739}
30740impl Default for ONBOARD_COMPUTER_STATUS_DATA {
30741 fn default() -> Self {
30742 Self::DEFAULT.clone()
30743 }
30744}
30745impl MessageData for ONBOARD_COMPUTER_STATUS_DATA {
30746 type Message = MavMessage;
30747 const ID: u32 = 390u32;
30748 const NAME: &'static str = "ONBOARD_COMPUTER_STATUS";
30749 const EXTRA_CRC: u8 = 156u8;
30750 const ENCODED_LEN: usize = 238usize;
30751 fn deser(
30752 _version: MavlinkVersion,
30753 __input: &[u8],
30754 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30755 let avail_len = __input.len();
30756 let mut payload_buf = [0; Self::ENCODED_LEN];
30757 let mut buf = if avail_len < Self::ENCODED_LEN {
30758 payload_buf[0..avail_len].copy_from_slice(__input);
30759 Bytes::new(&payload_buf)
30760 } else {
30761 Bytes::new(__input)
30762 };
30763 let mut __struct = Self::default();
30764 __struct.time_usec = buf.get_u64_le();
30765 __struct.uptime = buf.get_u32_le();
30766 __struct.ram_usage = buf.get_u32_le();
30767 __struct.ram_total = buf.get_u32_le();
30768 for v in &mut __struct.storage_type {
30769 let val = buf.get_u32_le();
30770 *v = val;
30771 }
30772 for v in &mut __struct.storage_usage {
30773 let val = buf.get_u32_le();
30774 *v = val;
30775 }
30776 for v in &mut __struct.storage_total {
30777 let val = buf.get_u32_le();
30778 *v = val;
30779 }
30780 for v in &mut __struct.link_type {
30781 let val = buf.get_u32_le();
30782 *v = val;
30783 }
30784 for v in &mut __struct.link_tx_rate {
30785 let val = buf.get_u32_le();
30786 *v = val;
30787 }
30788 for v in &mut __struct.link_rx_rate {
30789 let val = buf.get_u32_le();
30790 *v = val;
30791 }
30792 for v in &mut __struct.link_tx_max {
30793 let val = buf.get_u32_le();
30794 *v = val;
30795 }
30796 for v in &mut __struct.link_rx_max {
30797 let val = buf.get_u32_le();
30798 *v = val;
30799 }
30800 for v in &mut __struct.fan_speed {
30801 let val = buf.get_i16_le();
30802 *v = val;
30803 }
30804 __struct.mavtype = buf.get_u8();
30805 for v in &mut __struct.cpu_cores {
30806 let val = buf.get_u8();
30807 *v = val;
30808 }
30809 for v in &mut __struct.cpu_combined {
30810 let val = buf.get_u8();
30811 *v = val;
30812 }
30813 for v in &mut __struct.gpu_cores {
30814 let val = buf.get_u8();
30815 *v = val;
30816 }
30817 for v in &mut __struct.gpu_combined {
30818 let val = buf.get_u8();
30819 *v = val;
30820 }
30821 __struct.temperature_board = buf.get_i8();
30822 for v in &mut __struct.temperature_core {
30823 let val = buf.get_i8();
30824 *v = val;
30825 }
30826 Ok(__struct)
30827 }
30828 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30829 let mut __tmp = BytesMut::new(bytes);
30830 #[allow(clippy::absurd_extreme_comparisons)]
30831 #[allow(unused_comparisons)]
30832 if __tmp.remaining() < Self::ENCODED_LEN {
30833 panic!(
30834 "buffer is too small (need {} bytes, but got {})",
30835 Self::ENCODED_LEN,
30836 __tmp.remaining(),
30837 )
30838 }
30839 __tmp.put_u64_le(self.time_usec);
30840 __tmp.put_u32_le(self.uptime);
30841 __tmp.put_u32_le(self.ram_usage);
30842 __tmp.put_u32_le(self.ram_total);
30843 for val in &self.storage_type {
30844 __tmp.put_u32_le(*val);
30845 }
30846 for val in &self.storage_usage {
30847 __tmp.put_u32_le(*val);
30848 }
30849 for val in &self.storage_total {
30850 __tmp.put_u32_le(*val);
30851 }
30852 for val in &self.link_type {
30853 __tmp.put_u32_le(*val);
30854 }
30855 for val in &self.link_tx_rate {
30856 __tmp.put_u32_le(*val);
30857 }
30858 for val in &self.link_rx_rate {
30859 __tmp.put_u32_le(*val);
30860 }
30861 for val in &self.link_tx_max {
30862 __tmp.put_u32_le(*val);
30863 }
30864 for val in &self.link_rx_max {
30865 __tmp.put_u32_le(*val);
30866 }
30867 for val in &self.fan_speed {
30868 __tmp.put_i16_le(*val);
30869 }
30870 __tmp.put_u8(self.mavtype);
30871 for val in &self.cpu_cores {
30872 __tmp.put_u8(*val);
30873 }
30874 for val in &self.cpu_combined {
30875 __tmp.put_u8(*val);
30876 }
30877 for val in &self.gpu_cores {
30878 __tmp.put_u8(*val);
30879 }
30880 for val in &self.gpu_combined {
30881 __tmp.put_u8(*val);
30882 }
30883 __tmp.put_i8(self.temperature_board);
30884 for val in &self.temperature_core {
30885 __tmp.put_i8(*val);
30886 }
30887 if matches!(version, MavlinkVersion::V2) {
30888 let len = __tmp.len();
30889 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30890 } else {
30891 __tmp.len()
30892 }
30893 }
30894}
30895#[doc = "id: 83"]
30896#[doc = "Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way."]
30897#[derive(Debug, Clone, PartialEq)]
30898#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30899#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30900pub struct ATTITUDE_TARGET_DATA {
30901 #[doc = "Timestamp (time since system boot)."]
30902 pub time_boot_ms: u32,
30903 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
30904 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30905 pub q: [f32; 4],
30906 #[doc = "Body roll rate"]
30907 pub body_roll_rate: f32,
30908 #[doc = "Body pitch rate"]
30909 pub body_pitch_rate: f32,
30910 #[doc = "Body yaw rate"]
30911 pub body_yaw_rate: f32,
30912 #[doc = "Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)"]
30913 pub thrust: f32,
30914 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
30915 pub type_mask: AttitudeTargetTypemask,
30916}
30917impl ATTITUDE_TARGET_DATA {
30918 pub const ENCODED_LEN: usize = 37usize;
30919 pub const DEFAULT: Self = Self {
30920 time_boot_ms: 0_u32,
30921 q: [0.0_f32; 4usize],
30922 body_roll_rate: 0.0_f32,
30923 body_pitch_rate: 0.0_f32,
30924 body_yaw_rate: 0.0_f32,
30925 thrust: 0.0_f32,
30926 type_mask: AttitudeTargetTypemask::DEFAULT,
30927 };
30928 #[cfg(feature = "arbitrary")]
30929 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30930 use arbitrary::{Arbitrary, Unstructured};
30931 let mut buf = [0u8; 1024];
30932 rng.fill_bytes(&mut buf);
30933 let mut unstructured = Unstructured::new(&buf);
30934 Self::arbitrary(&mut unstructured).unwrap_or_default()
30935 }
30936}
30937impl Default for ATTITUDE_TARGET_DATA {
30938 fn default() -> Self {
30939 Self::DEFAULT.clone()
30940 }
30941}
30942impl MessageData for ATTITUDE_TARGET_DATA {
30943 type Message = MavMessage;
30944 const ID: u32 = 83u32;
30945 const NAME: &'static str = "ATTITUDE_TARGET";
30946 const EXTRA_CRC: u8 = 22u8;
30947 const ENCODED_LEN: usize = 37usize;
30948 fn deser(
30949 _version: MavlinkVersion,
30950 __input: &[u8],
30951 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30952 let avail_len = __input.len();
30953 let mut payload_buf = [0; Self::ENCODED_LEN];
30954 let mut buf = if avail_len < Self::ENCODED_LEN {
30955 payload_buf[0..avail_len].copy_from_slice(__input);
30956 Bytes::new(&payload_buf)
30957 } else {
30958 Bytes::new(__input)
30959 };
30960 let mut __struct = Self::default();
30961 __struct.time_boot_ms = buf.get_u32_le();
30962 for v in &mut __struct.q {
30963 let val = buf.get_f32_le();
30964 *v = val;
30965 }
30966 __struct.body_roll_rate = buf.get_f32_le();
30967 __struct.body_pitch_rate = buf.get_f32_le();
30968 __struct.body_yaw_rate = buf.get_f32_le();
30969 __struct.thrust = buf.get_f32_le();
30970 let tmp = buf.get_u8();
30971 __struct.type_mask = AttitudeTargetTypemask::from_bits(
30972 tmp & AttitudeTargetTypemask::all().bits(),
30973 )
30974 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30975 flag_type: "AttitudeTargetTypemask",
30976 value: tmp as u32,
30977 })?;
30978 Ok(__struct)
30979 }
30980 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30981 let mut __tmp = BytesMut::new(bytes);
30982 #[allow(clippy::absurd_extreme_comparisons)]
30983 #[allow(unused_comparisons)]
30984 if __tmp.remaining() < Self::ENCODED_LEN {
30985 panic!(
30986 "buffer is too small (need {} bytes, but got {})",
30987 Self::ENCODED_LEN,
30988 __tmp.remaining(),
30989 )
30990 }
30991 __tmp.put_u32_le(self.time_boot_ms);
30992 for val in &self.q {
30993 __tmp.put_f32_le(*val);
30994 }
30995 __tmp.put_f32_le(self.body_roll_rate);
30996 __tmp.put_f32_le(self.body_pitch_rate);
30997 __tmp.put_f32_le(self.body_yaw_rate);
30998 __tmp.put_f32_le(self.thrust);
30999 __tmp.put_u8(self.type_mask.bits());
31000 if matches!(version, MavlinkVersion::V2) {
31001 let len = __tmp.len();
31002 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31003 } else {
31004 __tmp.len()
31005 }
31006 }
31007}
31008#[doc = "id: 35"]
31009#[doc = "The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification."]
31010#[derive(Debug, Clone, PartialEq)]
31011#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31012#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31013pub struct RC_CHANNELS_RAW_DATA {
31014 #[doc = "Timestamp (time since system boot)."]
31015 pub time_boot_ms: u32,
31016 #[doc = "RC channel 1 value."]
31017 pub chan1_raw: u16,
31018 #[doc = "RC channel 2 value."]
31019 pub chan2_raw: u16,
31020 #[doc = "RC channel 3 value."]
31021 pub chan3_raw: u16,
31022 #[doc = "RC channel 4 value."]
31023 pub chan4_raw: u16,
31024 #[doc = "RC channel 5 value."]
31025 pub chan5_raw: u16,
31026 #[doc = "RC channel 6 value."]
31027 pub chan6_raw: u16,
31028 #[doc = "RC channel 7 value."]
31029 pub chan7_raw: u16,
31030 #[doc = "RC channel 8 value."]
31031 pub chan8_raw: u16,
31032 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
31033 pub port: u8,
31034 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
31035 pub rssi: u8,
31036}
31037impl RC_CHANNELS_RAW_DATA {
31038 pub const ENCODED_LEN: usize = 22usize;
31039 pub const DEFAULT: Self = Self {
31040 time_boot_ms: 0_u32,
31041 chan1_raw: 0_u16,
31042 chan2_raw: 0_u16,
31043 chan3_raw: 0_u16,
31044 chan4_raw: 0_u16,
31045 chan5_raw: 0_u16,
31046 chan6_raw: 0_u16,
31047 chan7_raw: 0_u16,
31048 chan8_raw: 0_u16,
31049 port: 0_u8,
31050 rssi: 0_u8,
31051 };
31052 #[cfg(feature = "arbitrary")]
31053 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31054 use arbitrary::{Arbitrary, Unstructured};
31055 let mut buf = [0u8; 1024];
31056 rng.fill_bytes(&mut buf);
31057 let mut unstructured = Unstructured::new(&buf);
31058 Self::arbitrary(&mut unstructured).unwrap_or_default()
31059 }
31060}
31061impl Default for RC_CHANNELS_RAW_DATA {
31062 fn default() -> Self {
31063 Self::DEFAULT.clone()
31064 }
31065}
31066impl MessageData for RC_CHANNELS_RAW_DATA {
31067 type Message = MavMessage;
31068 const ID: u32 = 35u32;
31069 const NAME: &'static str = "RC_CHANNELS_RAW";
31070 const EXTRA_CRC: u8 = 244u8;
31071 const ENCODED_LEN: usize = 22usize;
31072 fn deser(
31073 _version: MavlinkVersion,
31074 __input: &[u8],
31075 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31076 let avail_len = __input.len();
31077 let mut payload_buf = [0; Self::ENCODED_LEN];
31078 let mut buf = if avail_len < Self::ENCODED_LEN {
31079 payload_buf[0..avail_len].copy_from_slice(__input);
31080 Bytes::new(&payload_buf)
31081 } else {
31082 Bytes::new(__input)
31083 };
31084 let mut __struct = Self::default();
31085 __struct.time_boot_ms = buf.get_u32_le();
31086 __struct.chan1_raw = buf.get_u16_le();
31087 __struct.chan2_raw = buf.get_u16_le();
31088 __struct.chan3_raw = buf.get_u16_le();
31089 __struct.chan4_raw = buf.get_u16_le();
31090 __struct.chan5_raw = buf.get_u16_le();
31091 __struct.chan6_raw = buf.get_u16_le();
31092 __struct.chan7_raw = buf.get_u16_le();
31093 __struct.chan8_raw = buf.get_u16_le();
31094 __struct.port = buf.get_u8();
31095 __struct.rssi = buf.get_u8();
31096 Ok(__struct)
31097 }
31098 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31099 let mut __tmp = BytesMut::new(bytes);
31100 #[allow(clippy::absurd_extreme_comparisons)]
31101 #[allow(unused_comparisons)]
31102 if __tmp.remaining() < Self::ENCODED_LEN {
31103 panic!(
31104 "buffer is too small (need {} bytes, but got {})",
31105 Self::ENCODED_LEN,
31106 __tmp.remaining(),
31107 )
31108 }
31109 __tmp.put_u32_le(self.time_boot_ms);
31110 __tmp.put_u16_le(self.chan1_raw);
31111 __tmp.put_u16_le(self.chan2_raw);
31112 __tmp.put_u16_le(self.chan3_raw);
31113 __tmp.put_u16_le(self.chan4_raw);
31114 __tmp.put_u16_le(self.chan5_raw);
31115 __tmp.put_u16_le(self.chan6_raw);
31116 __tmp.put_u16_le(self.chan7_raw);
31117 __tmp.put_u16_le(self.chan8_raw);
31118 __tmp.put_u8(self.port);
31119 __tmp.put_u8(self.rssi);
31120 if matches!(version, MavlinkVersion::V2) {
31121 let len = __tmp.len();
31122 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31123 } else {
31124 __tmp.len()
31125 }
31126 }
31127}
31128#[doc = "id: 331"]
31129#[doc = "Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (<http://www.ros.org/reps/rep-0147.html>)."]
31130#[derive(Debug, Clone, PartialEq)]
31131#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31132#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31133pub struct ODOMETRY_DATA {
31134 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
31135 pub time_usec: u64,
31136 #[doc = "X Position"]
31137 pub x: f32,
31138 #[doc = "Y Position"]
31139 pub y: f32,
31140 #[doc = "Z Position"]
31141 pub z: f32,
31142 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)"]
31143 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31144 pub q: [f32; 4],
31145 #[doc = "X linear speed"]
31146 pub vx: f32,
31147 #[doc = "Y linear speed"]
31148 pub vy: f32,
31149 #[doc = "Z linear speed"]
31150 pub vz: f32,
31151 #[doc = "Roll angular speed"]
31152 pub rollspeed: f32,
31153 #[doc = "Pitch angular speed"]
31154 pub pitchspeed: f32,
31155 #[doc = "Yaw angular speed"]
31156 pub yawspeed: f32,
31157 #[doc = "Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
31158 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31159 pub pose_covariance: [f32; 21],
31160 #[doc = "Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
31161 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31162 pub velocity_covariance: [f32; 21],
31163 #[doc = "Coordinate frame of reference for the pose data."]
31164 pub frame_id: MavFrame,
31165 #[doc = "Coordinate frame of reference for the velocity in free space (twist) data."]
31166 pub child_frame_id: MavFrame,
31167 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
31168 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31169 pub reset_counter: u8,
31170 #[doc = "Type of estimator that is providing the odometry."]
31171 #[cfg_attr(feature = "serde", serde(default))]
31172 pub estimator_type: MavEstimatorType,
31173 #[doc = "Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality"]
31174 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31175 pub quality: i8,
31176}
31177impl ODOMETRY_DATA {
31178 pub const ENCODED_LEN: usize = 233usize;
31179 pub const DEFAULT: Self = Self {
31180 time_usec: 0_u64,
31181 x: 0.0_f32,
31182 y: 0.0_f32,
31183 z: 0.0_f32,
31184 q: [0.0_f32; 4usize],
31185 vx: 0.0_f32,
31186 vy: 0.0_f32,
31187 vz: 0.0_f32,
31188 rollspeed: 0.0_f32,
31189 pitchspeed: 0.0_f32,
31190 yawspeed: 0.0_f32,
31191 pose_covariance: [0.0_f32; 21usize],
31192 velocity_covariance: [0.0_f32; 21usize],
31193 frame_id: MavFrame::DEFAULT,
31194 child_frame_id: MavFrame::DEFAULT,
31195 reset_counter: 0_u8,
31196 estimator_type: MavEstimatorType::DEFAULT,
31197 quality: 0_i8,
31198 };
31199 #[cfg(feature = "arbitrary")]
31200 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31201 use arbitrary::{Arbitrary, Unstructured};
31202 let mut buf = [0u8; 1024];
31203 rng.fill_bytes(&mut buf);
31204 let mut unstructured = Unstructured::new(&buf);
31205 Self::arbitrary(&mut unstructured).unwrap_or_default()
31206 }
31207}
31208impl Default for ODOMETRY_DATA {
31209 fn default() -> Self {
31210 Self::DEFAULT.clone()
31211 }
31212}
31213impl MessageData for ODOMETRY_DATA {
31214 type Message = MavMessage;
31215 const ID: u32 = 331u32;
31216 const NAME: &'static str = "ODOMETRY";
31217 const EXTRA_CRC: u8 = 91u8;
31218 const ENCODED_LEN: usize = 233usize;
31219 fn deser(
31220 _version: MavlinkVersion,
31221 __input: &[u8],
31222 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31223 let avail_len = __input.len();
31224 let mut payload_buf = [0; Self::ENCODED_LEN];
31225 let mut buf = if avail_len < Self::ENCODED_LEN {
31226 payload_buf[0..avail_len].copy_from_slice(__input);
31227 Bytes::new(&payload_buf)
31228 } else {
31229 Bytes::new(__input)
31230 };
31231 let mut __struct = Self::default();
31232 __struct.time_usec = buf.get_u64_le();
31233 __struct.x = buf.get_f32_le();
31234 __struct.y = buf.get_f32_le();
31235 __struct.z = buf.get_f32_le();
31236 for v in &mut __struct.q {
31237 let val = buf.get_f32_le();
31238 *v = val;
31239 }
31240 __struct.vx = buf.get_f32_le();
31241 __struct.vy = buf.get_f32_le();
31242 __struct.vz = buf.get_f32_le();
31243 __struct.rollspeed = buf.get_f32_le();
31244 __struct.pitchspeed = buf.get_f32_le();
31245 __struct.yawspeed = buf.get_f32_le();
31246 for v in &mut __struct.pose_covariance {
31247 let val = buf.get_f32_le();
31248 *v = val;
31249 }
31250 for v in &mut __struct.velocity_covariance {
31251 let val = buf.get_f32_le();
31252 *v = val;
31253 }
31254 let tmp = buf.get_u8();
31255 __struct.frame_id =
31256 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31257 enum_type: "MavFrame",
31258 value: tmp as u32,
31259 })?;
31260 let tmp = buf.get_u8();
31261 __struct.child_frame_id =
31262 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31263 enum_type: "MavFrame",
31264 value: tmp as u32,
31265 })?;
31266 __struct.reset_counter = buf.get_u8();
31267 let tmp = buf.get_u8();
31268 __struct.estimator_type =
31269 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31270 enum_type: "MavEstimatorType",
31271 value: tmp as u32,
31272 })?;
31273 __struct.quality = buf.get_i8();
31274 Ok(__struct)
31275 }
31276 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31277 let mut __tmp = BytesMut::new(bytes);
31278 #[allow(clippy::absurd_extreme_comparisons)]
31279 #[allow(unused_comparisons)]
31280 if __tmp.remaining() < Self::ENCODED_LEN {
31281 panic!(
31282 "buffer is too small (need {} bytes, but got {})",
31283 Self::ENCODED_LEN,
31284 __tmp.remaining(),
31285 )
31286 }
31287 __tmp.put_u64_le(self.time_usec);
31288 __tmp.put_f32_le(self.x);
31289 __tmp.put_f32_le(self.y);
31290 __tmp.put_f32_le(self.z);
31291 for val in &self.q {
31292 __tmp.put_f32_le(*val);
31293 }
31294 __tmp.put_f32_le(self.vx);
31295 __tmp.put_f32_le(self.vy);
31296 __tmp.put_f32_le(self.vz);
31297 __tmp.put_f32_le(self.rollspeed);
31298 __tmp.put_f32_le(self.pitchspeed);
31299 __tmp.put_f32_le(self.yawspeed);
31300 for val in &self.pose_covariance {
31301 __tmp.put_f32_le(*val);
31302 }
31303 for val in &self.velocity_covariance {
31304 __tmp.put_f32_le(*val);
31305 }
31306 __tmp.put_u8(self.frame_id as u8);
31307 __tmp.put_u8(self.child_frame_id as u8);
31308 __tmp.put_u8(self.reset_counter);
31309 __tmp.put_u8(self.estimator_type as u8);
31310 __tmp.put_i8(self.quality);
31311 if matches!(version, MavlinkVersion::V2) {
31312 let len = __tmp.len();
31313 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31314 } else {
31315 __tmp.len()
31316 }
31317 }
31318}
31319#[doc = "id: 103"]
31320#[doc = "Speed estimate from a vision source."]
31321#[derive(Debug, Clone, PartialEq)]
31322#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31323#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31324pub struct VISION_SPEED_ESTIMATE_DATA {
31325 #[doc = "Timestamp (UNIX time or time since system boot)"]
31326 pub usec: u64,
31327 #[doc = "Global X speed"]
31328 pub x: f32,
31329 #[doc = "Global Y speed"]
31330 pub y: f32,
31331 #[doc = "Global Z speed"]
31332 pub z: f32,
31333 #[doc = "Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array."]
31334 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31335 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31336 pub covariance: [f32; 9],
31337 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
31338 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31339 pub reset_counter: u8,
31340}
31341impl VISION_SPEED_ESTIMATE_DATA {
31342 pub const ENCODED_LEN: usize = 57usize;
31343 pub const DEFAULT: Self = Self {
31344 usec: 0_u64,
31345 x: 0.0_f32,
31346 y: 0.0_f32,
31347 z: 0.0_f32,
31348 covariance: [0.0_f32; 9usize],
31349 reset_counter: 0_u8,
31350 };
31351 #[cfg(feature = "arbitrary")]
31352 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31353 use arbitrary::{Arbitrary, Unstructured};
31354 let mut buf = [0u8; 1024];
31355 rng.fill_bytes(&mut buf);
31356 let mut unstructured = Unstructured::new(&buf);
31357 Self::arbitrary(&mut unstructured).unwrap_or_default()
31358 }
31359}
31360impl Default for VISION_SPEED_ESTIMATE_DATA {
31361 fn default() -> Self {
31362 Self::DEFAULT.clone()
31363 }
31364}
31365impl MessageData for VISION_SPEED_ESTIMATE_DATA {
31366 type Message = MavMessage;
31367 const ID: u32 = 103u32;
31368 const NAME: &'static str = "VISION_SPEED_ESTIMATE";
31369 const EXTRA_CRC: u8 = 208u8;
31370 const ENCODED_LEN: usize = 57usize;
31371 fn deser(
31372 _version: MavlinkVersion,
31373 __input: &[u8],
31374 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31375 let avail_len = __input.len();
31376 let mut payload_buf = [0; Self::ENCODED_LEN];
31377 let mut buf = if avail_len < Self::ENCODED_LEN {
31378 payload_buf[0..avail_len].copy_from_slice(__input);
31379 Bytes::new(&payload_buf)
31380 } else {
31381 Bytes::new(__input)
31382 };
31383 let mut __struct = Self::default();
31384 __struct.usec = buf.get_u64_le();
31385 __struct.x = buf.get_f32_le();
31386 __struct.y = buf.get_f32_le();
31387 __struct.z = buf.get_f32_le();
31388 for v in &mut __struct.covariance {
31389 let val = buf.get_f32_le();
31390 *v = val;
31391 }
31392 __struct.reset_counter = buf.get_u8();
31393 Ok(__struct)
31394 }
31395 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31396 let mut __tmp = BytesMut::new(bytes);
31397 #[allow(clippy::absurd_extreme_comparisons)]
31398 #[allow(unused_comparisons)]
31399 if __tmp.remaining() < Self::ENCODED_LEN {
31400 panic!(
31401 "buffer is too small (need {} bytes, but got {})",
31402 Self::ENCODED_LEN,
31403 __tmp.remaining(),
31404 )
31405 }
31406 __tmp.put_u64_le(self.usec);
31407 __tmp.put_f32_le(self.x);
31408 __tmp.put_f32_le(self.y);
31409 __tmp.put_f32_le(self.z);
31410 for val in &self.covariance {
31411 __tmp.put_f32_le(*val);
31412 }
31413 __tmp.put_u8(self.reset_counter);
31414 if matches!(version, MavlinkVersion::V2) {
31415 let len = __tmp.len();
31416 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31417 } else {
31418 __tmp.len()
31419 }
31420 }
31421}
31422#[doc = "id: 286"]
31423#[doc = "Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis."]
31424#[derive(Debug, Clone, PartialEq)]
31425#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31426#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31427pub struct AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
31428 #[doc = "Timestamp (time since system boot)."]
31429 pub time_boot_us: u64,
31430 #[doc = "Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention)."]
31431 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31432 pub q: [f32; 4],
31433 #[doc = "Estimated delay of the attitude data. 0 if unknown."]
31434 pub q_estimated_delay_us: u32,
31435 #[doc = "X Speed in NED (North, East, Down). NAN if unknown."]
31436 pub vx: f32,
31437 #[doc = "Y Speed in NED (North, East, Down). NAN if unknown."]
31438 pub vy: f32,
31439 #[doc = "Z Speed in NED (North, East, Down). NAN if unknown."]
31440 pub vz: f32,
31441 #[doc = "Estimated delay of the speed data. 0 if unknown."]
31442 pub v_estimated_delay_us: u32,
31443 #[doc = "Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing."]
31444 pub feed_forward_angular_velocity_z: f32,
31445 #[doc = "Bitmap indicating which estimator outputs are valid."]
31446 pub estimator_status: EstimatorStatusFlags,
31447 #[doc = "System ID"]
31448 pub target_system: u8,
31449 #[doc = "Component ID"]
31450 pub target_component: u8,
31451 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
31452 pub landed_state: MavLandedState,
31453 #[doc = "Z component of angular velocity in NED (North, East, Down). NaN if unknown."]
31454 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31455 pub angular_velocity_z: f32,
31456}
31457impl AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
31458 pub const ENCODED_LEN: usize = 57usize;
31459 pub const DEFAULT: Self = Self {
31460 time_boot_us: 0_u64,
31461 q: [0.0_f32; 4usize],
31462 q_estimated_delay_us: 0_u32,
31463 vx: 0.0_f32,
31464 vy: 0.0_f32,
31465 vz: 0.0_f32,
31466 v_estimated_delay_us: 0_u32,
31467 feed_forward_angular_velocity_z: 0.0_f32,
31468 estimator_status: EstimatorStatusFlags::DEFAULT,
31469 target_system: 0_u8,
31470 target_component: 0_u8,
31471 landed_state: MavLandedState::DEFAULT,
31472 angular_velocity_z: 0.0_f32,
31473 };
31474 #[cfg(feature = "arbitrary")]
31475 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31476 use arbitrary::{Arbitrary, Unstructured};
31477 let mut buf = [0u8; 1024];
31478 rng.fill_bytes(&mut buf);
31479 let mut unstructured = Unstructured::new(&buf);
31480 Self::arbitrary(&mut unstructured).unwrap_or_default()
31481 }
31482}
31483impl Default for AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
31484 fn default() -> Self {
31485 Self::DEFAULT.clone()
31486 }
31487}
31488impl MessageData for AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
31489 type Message = MavMessage;
31490 const ID: u32 = 286u32;
31491 const NAME: &'static str = "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE";
31492 const EXTRA_CRC: u8 = 210u8;
31493 const ENCODED_LEN: usize = 57usize;
31494 fn deser(
31495 _version: MavlinkVersion,
31496 __input: &[u8],
31497 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31498 let avail_len = __input.len();
31499 let mut payload_buf = [0; Self::ENCODED_LEN];
31500 let mut buf = if avail_len < Self::ENCODED_LEN {
31501 payload_buf[0..avail_len].copy_from_slice(__input);
31502 Bytes::new(&payload_buf)
31503 } else {
31504 Bytes::new(__input)
31505 };
31506 let mut __struct = Self::default();
31507 __struct.time_boot_us = buf.get_u64_le();
31508 for v in &mut __struct.q {
31509 let val = buf.get_f32_le();
31510 *v = val;
31511 }
31512 __struct.q_estimated_delay_us = buf.get_u32_le();
31513 __struct.vx = buf.get_f32_le();
31514 __struct.vy = buf.get_f32_le();
31515 __struct.vz = buf.get_f32_le();
31516 __struct.v_estimated_delay_us = buf.get_u32_le();
31517 __struct.feed_forward_angular_velocity_z = buf.get_f32_le();
31518 let tmp = buf.get_u16_le();
31519 __struct.estimator_status = EstimatorStatusFlags::from_bits(
31520 tmp & EstimatorStatusFlags::all().bits(),
31521 )
31522 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
31523 flag_type: "EstimatorStatusFlags",
31524 value: tmp as u32,
31525 })?;
31526 __struct.target_system = buf.get_u8();
31527 __struct.target_component = buf.get_u8();
31528 let tmp = buf.get_u8();
31529 __struct.landed_state =
31530 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31531 enum_type: "MavLandedState",
31532 value: tmp as u32,
31533 })?;
31534 __struct.angular_velocity_z = buf.get_f32_le();
31535 Ok(__struct)
31536 }
31537 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31538 let mut __tmp = BytesMut::new(bytes);
31539 #[allow(clippy::absurd_extreme_comparisons)]
31540 #[allow(unused_comparisons)]
31541 if __tmp.remaining() < Self::ENCODED_LEN {
31542 panic!(
31543 "buffer is too small (need {} bytes, but got {})",
31544 Self::ENCODED_LEN,
31545 __tmp.remaining(),
31546 )
31547 }
31548 __tmp.put_u64_le(self.time_boot_us);
31549 for val in &self.q {
31550 __tmp.put_f32_le(*val);
31551 }
31552 __tmp.put_u32_le(self.q_estimated_delay_us);
31553 __tmp.put_f32_le(self.vx);
31554 __tmp.put_f32_le(self.vy);
31555 __tmp.put_f32_le(self.vz);
31556 __tmp.put_u32_le(self.v_estimated_delay_us);
31557 __tmp.put_f32_le(self.feed_forward_angular_velocity_z);
31558 __tmp.put_u16_le(self.estimator_status.bits());
31559 __tmp.put_u8(self.target_system);
31560 __tmp.put_u8(self.target_component);
31561 __tmp.put_u8(self.landed_state as u8);
31562 __tmp.put_f32_le(self.angular_velocity_z);
31563 if matches!(version, MavlinkVersion::V2) {
31564 let len = __tmp.len();
31565 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31566 } else {
31567 __tmp.len()
31568 }
31569 }
31570}
31571#[doc = "id: 141"]
31572#[doc = "The current system altitude."]
31573#[derive(Debug, Clone, PartialEq)]
31574#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31575#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31576pub struct ALTITUDE_DATA {
31577 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
31578 pub time_usec: u64,
31579 #[doc = "This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights."]
31580 pub altitude_monotonic: f32,
31581 #[doc = "This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude."]
31582 pub altitude_amsl: f32,
31583 #[doc = "This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive."]
31584 pub altitude_local: f32,
31585 #[doc = "This is the altitude above the home position. It resets on each change of the current home position."]
31586 pub altitude_relative: f32,
31587 #[doc = "This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown."]
31588 pub altitude_terrain: f32,
31589 #[doc = "This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available."]
31590 pub bottom_clearance: f32,
31591}
31592impl ALTITUDE_DATA {
31593 pub const ENCODED_LEN: usize = 32usize;
31594 pub const DEFAULT: Self = Self {
31595 time_usec: 0_u64,
31596 altitude_monotonic: 0.0_f32,
31597 altitude_amsl: 0.0_f32,
31598 altitude_local: 0.0_f32,
31599 altitude_relative: 0.0_f32,
31600 altitude_terrain: 0.0_f32,
31601 bottom_clearance: 0.0_f32,
31602 };
31603 #[cfg(feature = "arbitrary")]
31604 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31605 use arbitrary::{Arbitrary, Unstructured};
31606 let mut buf = [0u8; 1024];
31607 rng.fill_bytes(&mut buf);
31608 let mut unstructured = Unstructured::new(&buf);
31609 Self::arbitrary(&mut unstructured).unwrap_or_default()
31610 }
31611}
31612impl Default for ALTITUDE_DATA {
31613 fn default() -> Self {
31614 Self::DEFAULT.clone()
31615 }
31616}
31617impl MessageData for ALTITUDE_DATA {
31618 type Message = MavMessage;
31619 const ID: u32 = 141u32;
31620 const NAME: &'static str = "ALTITUDE";
31621 const EXTRA_CRC: u8 = 47u8;
31622 const ENCODED_LEN: usize = 32usize;
31623 fn deser(
31624 _version: MavlinkVersion,
31625 __input: &[u8],
31626 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31627 let avail_len = __input.len();
31628 let mut payload_buf = [0; Self::ENCODED_LEN];
31629 let mut buf = if avail_len < Self::ENCODED_LEN {
31630 payload_buf[0..avail_len].copy_from_slice(__input);
31631 Bytes::new(&payload_buf)
31632 } else {
31633 Bytes::new(__input)
31634 };
31635 let mut __struct = Self::default();
31636 __struct.time_usec = buf.get_u64_le();
31637 __struct.altitude_monotonic = buf.get_f32_le();
31638 __struct.altitude_amsl = buf.get_f32_le();
31639 __struct.altitude_local = buf.get_f32_le();
31640 __struct.altitude_relative = buf.get_f32_le();
31641 __struct.altitude_terrain = buf.get_f32_le();
31642 __struct.bottom_clearance = buf.get_f32_le();
31643 Ok(__struct)
31644 }
31645 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31646 let mut __tmp = BytesMut::new(bytes);
31647 #[allow(clippy::absurd_extreme_comparisons)]
31648 #[allow(unused_comparisons)]
31649 if __tmp.remaining() < Self::ENCODED_LEN {
31650 panic!(
31651 "buffer is too small (need {} bytes, but got {})",
31652 Self::ENCODED_LEN,
31653 __tmp.remaining(),
31654 )
31655 }
31656 __tmp.put_u64_le(self.time_usec);
31657 __tmp.put_f32_le(self.altitude_monotonic);
31658 __tmp.put_f32_le(self.altitude_amsl);
31659 __tmp.put_f32_le(self.altitude_local);
31660 __tmp.put_f32_le(self.altitude_relative);
31661 __tmp.put_f32_le(self.altitude_terrain);
31662 __tmp.put_f32_le(self.bottom_clearance);
31663 if matches!(version, MavlinkVersion::V2) {
31664 let len = __tmp.len();
31665 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31666 } else {
31667 __tmp.len()
31668 }
31669 }
31670}
31671#[doc = "id: 12902"]
31672#[doc = "Data for filling the OpenDroneID Authentication message. The Authentication Message defines a field that can provide a means of authenticity for the identity of the UAS (Unmanned Aircraft System). The Authentication message can have two different formats. For data page 0, the fields PageCount, Length and TimeStamp are present and AuthData is only 17 bytes. For data page 1 through 15, PageCount, Length and TimeStamp are not present and the size of AuthData is 23 bytes."]
31673#[derive(Debug, Clone, PartialEq)]
31674#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31675#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31676pub struct OPEN_DRONE_ID_AUTHENTICATION_DATA {
31677 #[doc = "This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
31678 pub timestamp: u32,
31679 #[doc = "System ID (0 for broadcast)."]
31680 pub target_system: u8,
31681 #[doc = "Component ID (0 for broadcast)."]
31682 pub target_component: u8,
31683 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
31684 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31685 pub id_or_mac: [u8; 20],
31686 #[doc = "Indicates the type of authentication."]
31687 pub authentication_type: MavOdidAuthType,
31688 #[doc = "Allowed range is 0 - 15."]
31689 pub data_page: u8,
31690 #[doc = "This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at <https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h>."]
31691 pub last_page_index: u8,
31692 #[doc = "This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at <https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h>."]
31693 pub length: u8,
31694 #[doc = "Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field."]
31695 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31696 pub authentication_data: [u8; 23],
31697}
31698impl OPEN_DRONE_ID_AUTHENTICATION_DATA {
31699 pub const ENCODED_LEN: usize = 53usize;
31700 pub const DEFAULT: Self = Self {
31701 timestamp: 0_u32,
31702 target_system: 0_u8,
31703 target_component: 0_u8,
31704 id_or_mac: [0_u8; 20usize],
31705 authentication_type: MavOdidAuthType::DEFAULT,
31706 data_page: 0_u8,
31707 last_page_index: 0_u8,
31708 length: 0_u8,
31709 authentication_data: [0_u8; 23usize],
31710 };
31711 #[cfg(feature = "arbitrary")]
31712 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31713 use arbitrary::{Arbitrary, Unstructured};
31714 let mut buf = [0u8; 1024];
31715 rng.fill_bytes(&mut buf);
31716 let mut unstructured = Unstructured::new(&buf);
31717 Self::arbitrary(&mut unstructured).unwrap_or_default()
31718 }
31719}
31720impl Default for OPEN_DRONE_ID_AUTHENTICATION_DATA {
31721 fn default() -> Self {
31722 Self::DEFAULT.clone()
31723 }
31724}
31725impl MessageData for OPEN_DRONE_ID_AUTHENTICATION_DATA {
31726 type Message = MavMessage;
31727 const ID: u32 = 12902u32;
31728 const NAME: &'static str = "OPEN_DRONE_ID_AUTHENTICATION";
31729 const EXTRA_CRC: u8 = 140u8;
31730 const ENCODED_LEN: usize = 53usize;
31731 fn deser(
31732 _version: MavlinkVersion,
31733 __input: &[u8],
31734 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31735 let avail_len = __input.len();
31736 let mut payload_buf = [0; Self::ENCODED_LEN];
31737 let mut buf = if avail_len < Self::ENCODED_LEN {
31738 payload_buf[0..avail_len].copy_from_slice(__input);
31739 Bytes::new(&payload_buf)
31740 } else {
31741 Bytes::new(__input)
31742 };
31743 let mut __struct = Self::default();
31744 __struct.timestamp = buf.get_u32_le();
31745 __struct.target_system = buf.get_u8();
31746 __struct.target_component = buf.get_u8();
31747 for v in &mut __struct.id_or_mac {
31748 let val = buf.get_u8();
31749 *v = val;
31750 }
31751 let tmp = buf.get_u8();
31752 __struct.authentication_type =
31753 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31754 enum_type: "MavOdidAuthType",
31755 value: tmp as u32,
31756 })?;
31757 __struct.data_page = buf.get_u8();
31758 __struct.last_page_index = buf.get_u8();
31759 __struct.length = buf.get_u8();
31760 for v in &mut __struct.authentication_data {
31761 let val = buf.get_u8();
31762 *v = val;
31763 }
31764 Ok(__struct)
31765 }
31766 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31767 let mut __tmp = BytesMut::new(bytes);
31768 #[allow(clippy::absurd_extreme_comparisons)]
31769 #[allow(unused_comparisons)]
31770 if __tmp.remaining() < Self::ENCODED_LEN {
31771 panic!(
31772 "buffer is too small (need {} bytes, but got {})",
31773 Self::ENCODED_LEN,
31774 __tmp.remaining(),
31775 )
31776 }
31777 __tmp.put_u32_le(self.timestamp);
31778 __tmp.put_u8(self.target_system);
31779 __tmp.put_u8(self.target_component);
31780 for val in &self.id_or_mac {
31781 __tmp.put_u8(*val);
31782 }
31783 __tmp.put_u8(self.authentication_type as u8);
31784 __tmp.put_u8(self.data_page);
31785 __tmp.put_u8(self.last_page_index);
31786 __tmp.put_u8(self.length);
31787 for val in &self.authentication_data {
31788 __tmp.put_u8(*val);
31789 }
31790 if matches!(version, MavlinkVersion::V2) {
31791 let len = __tmp.len();
31792 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31793 } else {
31794 __tmp.len()
31795 }
31796 }
31797}
31798#[doc = "id: 21"]
31799#[doc = "Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
31800#[derive(Debug, Clone, PartialEq)]
31801#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31802#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31803pub struct PARAM_REQUEST_LIST_DATA {
31804 #[doc = "System ID"]
31805 pub target_system: u8,
31806 #[doc = "Component ID"]
31807 pub target_component: u8,
31808}
31809impl PARAM_REQUEST_LIST_DATA {
31810 pub const ENCODED_LEN: usize = 2usize;
31811 pub const DEFAULT: Self = Self {
31812 target_system: 0_u8,
31813 target_component: 0_u8,
31814 };
31815 #[cfg(feature = "arbitrary")]
31816 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31817 use arbitrary::{Arbitrary, Unstructured};
31818 let mut buf = [0u8; 1024];
31819 rng.fill_bytes(&mut buf);
31820 let mut unstructured = Unstructured::new(&buf);
31821 Self::arbitrary(&mut unstructured).unwrap_or_default()
31822 }
31823}
31824impl Default for PARAM_REQUEST_LIST_DATA {
31825 fn default() -> Self {
31826 Self::DEFAULT.clone()
31827 }
31828}
31829impl MessageData for PARAM_REQUEST_LIST_DATA {
31830 type Message = MavMessage;
31831 const ID: u32 = 21u32;
31832 const NAME: &'static str = "PARAM_REQUEST_LIST";
31833 const EXTRA_CRC: u8 = 159u8;
31834 const ENCODED_LEN: usize = 2usize;
31835 fn deser(
31836 _version: MavlinkVersion,
31837 __input: &[u8],
31838 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31839 let avail_len = __input.len();
31840 let mut payload_buf = [0; Self::ENCODED_LEN];
31841 let mut buf = if avail_len < Self::ENCODED_LEN {
31842 payload_buf[0..avail_len].copy_from_slice(__input);
31843 Bytes::new(&payload_buf)
31844 } else {
31845 Bytes::new(__input)
31846 };
31847 let mut __struct = Self::default();
31848 __struct.target_system = buf.get_u8();
31849 __struct.target_component = buf.get_u8();
31850 Ok(__struct)
31851 }
31852 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31853 let mut __tmp = BytesMut::new(bytes);
31854 #[allow(clippy::absurd_extreme_comparisons)]
31855 #[allow(unused_comparisons)]
31856 if __tmp.remaining() < Self::ENCODED_LEN {
31857 panic!(
31858 "buffer is too small (need {} bytes, but got {})",
31859 Self::ENCODED_LEN,
31860 __tmp.remaining(),
31861 )
31862 }
31863 __tmp.put_u8(self.target_system);
31864 __tmp.put_u8(self.target_component);
31865 if matches!(version, MavlinkVersion::V2) {
31866 let len = __tmp.len();
31867 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31868 } else {
31869 __tmp.len()
31870 }
31871 }
31872}
31873#[doc = "id: 89"]
31874#[doc = "The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
31875#[derive(Debug, Clone, PartialEq)]
31876#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31877#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31878pub struct LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
31879 #[doc = "Timestamp (time since system boot)."]
31880 pub time_boot_ms: u32,
31881 #[doc = "X Position"]
31882 pub x: f32,
31883 #[doc = "Y Position"]
31884 pub y: f32,
31885 #[doc = "Z Position"]
31886 pub z: f32,
31887 #[doc = "Roll"]
31888 pub roll: f32,
31889 #[doc = "Pitch"]
31890 pub pitch: f32,
31891 #[doc = "Yaw"]
31892 pub yaw: f32,
31893}
31894impl LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
31895 pub const ENCODED_LEN: usize = 28usize;
31896 pub const DEFAULT: Self = Self {
31897 time_boot_ms: 0_u32,
31898 x: 0.0_f32,
31899 y: 0.0_f32,
31900 z: 0.0_f32,
31901 roll: 0.0_f32,
31902 pitch: 0.0_f32,
31903 yaw: 0.0_f32,
31904 };
31905 #[cfg(feature = "arbitrary")]
31906 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31907 use arbitrary::{Arbitrary, Unstructured};
31908 let mut buf = [0u8; 1024];
31909 rng.fill_bytes(&mut buf);
31910 let mut unstructured = Unstructured::new(&buf);
31911 Self::arbitrary(&mut unstructured).unwrap_or_default()
31912 }
31913}
31914impl Default for LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
31915 fn default() -> Self {
31916 Self::DEFAULT.clone()
31917 }
31918}
31919impl MessageData for LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
31920 type Message = MavMessage;
31921 const ID: u32 = 89u32;
31922 const NAME: &'static str = "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET";
31923 const EXTRA_CRC: u8 = 231u8;
31924 const ENCODED_LEN: usize = 28usize;
31925 fn deser(
31926 _version: MavlinkVersion,
31927 __input: &[u8],
31928 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31929 let avail_len = __input.len();
31930 let mut payload_buf = [0; Self::ENCODED_LEN];
31931 let mut buf = if avail_len < Self::ENCODED_LEN {
31932 payload_buf[0..avail_len].copy_from_slice(__input);
31933 Bytes::new(&payload_buf)
31934 } else {
31935 Bytes::new(__input)
31936 };
31937 let mut __struct = Self::default();
31938 __struct.time_boot_ms = buf.get_u32_le();
31939 __struct.x = buf.get_f32_le();
31940 __struct.y = buf.get_f32_le();
31941 __struct.z = buf.get_f32_le();
31942 __struct.roll = buf.get_f32_le();
31943 __struct.pitch = buf.get_f32_le();
31944 __struct.yaw = buf.get_f32_le();
31945 Ok(__struct)
31946 }
31947 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31948 let mut __tmp = BytesMut::new(bytes);
31949 #[allow(clippy::absurd_extreme_comparisons)]
31950 #[allow(unused_comparisons)]
31951 if __tmp.remaining() < Self::ENCODED_LEN {
31952 panic!(
31953 "buffer is too small (need {} bytes, but got {})",
31954 Self::ENCODED_LEN,
31955 __tmp.remaining(),
31956 )
31957 }
31958 __tmp.put_u32_le(self.time_boot_ms);
31959 __tmp.put_f32_le(self.x);
31960 __tmp.put_f32_le(self.y);
31961 __tmp.put_f32_le(self.z);
31962 __tmp.put_f32_le(self.roll);
31963 __tmp.put_f32_le(self.pitch);
31964 __tmp.put_f32_le(self.yaw);
31965 if matches!(version, MavlinkVersion::V2) {
31966 let len = __tmp.len();
31967 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31968 } else {
31969 __tmp.len()
31970 }
31971 }
31972}
31973#[derive(Clone, PartialEq, Debug)]
31974#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31975#[cfg_attr(feature = "serde", serde(tag = "type"))]
31976#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31977#[repr(u32)]
31978pub enum MavMessage {
31979 ACTUATOR_CONTROL_TARGET(ACTUATOR_CONTROL_TARGET_DATA),
31980 LOG_ERASE(LOG_ERASE_DATA),
31981 CAMERA_TRACKING_IMAGE_STATUS(CAMERA_TRACKING_IMAGE_STATUS_DATA),
31982 MISSION_WRITE_PARTIAL_LIST(MISSION_WRITE_PARTIAL_LIST_DATA),
31983 SCALED_PRESSURE(SCALED_PRESSURE_DATA),
31984 TRAJECTORY_REPRESENTATION_BEZIER(TRAJECTORY_REPRESENTATION_BEZIER_DATA),
31985 ORBIT_EXECUTION_STATUS(ORBIT_EXECUTION_STATUS_DATA),
31986 AUTH_KEY(AUTH_KEY_DATA),
31987 FILE_TRANSFER_PROTOCOL(FILE_TRANSFER_PROTOCOL_DATA),
31988 SYS_STATUS(SYS_STATUS_DATA),
31989 LOG_REQUEST_END(LOG_REQUEST_END_DATA),
31990 TERRAIN_DATA(TERRAIN_DATA_DATA),
31991 LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA),
31992 NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA),
31993 LANDING_TARGET(LANDING_TARGET_DATA),
31994 ATT_POS_MOCAP(ATT_POS_MOCAP_DATA),
31995 SCALED_IMU3(SCALED_IMU3_DATA),
31996 MEMORY_VECT(MEMORY_VECT_DATA),
31997 TERRAIN_REQUEST(TERRAIN_REQUEST_DATA),
31998 V2_EXTENSION(V2_EXTENSION_DATA),
31999 DEBUG_VECT(DEBUG_VECT_DATA),
32000 MANUAL_CONTROL(MANUAL_CONTROL_DATA),
32001 AIS_VESSEL(AIS_VESSEL_DATA),
32002 UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA),
32003 SET_GPS_GLOBAL_ORIGIN(SET_GPS_GLOBAL_ORIGIN_DATA),
32004 SCALED_PRESSURE2(SCALED_PRESSURE2_DATA),
32005 CAMERA_CAPTURE_STATUS(CAMERA_CAPTURE_STATUS_DATA),
32006 WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA),
32007 MISSION_REQUEST_LIST(MISSION_REQUEST_LIST_DATA),
32008 MISSION_ACK(MISSION_ACK_DATA),
32009 ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA),
32010 UAVIONIX_ADSB_OUT_CFG(UAVIONIX_ADSB_OUT_CFG_DATA),
32011 EFI_STATUS(EFI_STATUS_DATA),
32012 OPEN_DRONE_ID_LOCATION(OPEN_DRONE_ID_LOCATION_DATA),
32013 CAMERA_THERMAL_RANGE(CAMERA_THERMAL_RANGE_DATA),
32014 LOGGING_ACK(LOGGING_ACK_DATA),
32015 HIL_CONTROLS(HIL_CONTROLS_DATA),
32016 GENERATOR_STATUS(GENERATOR_STATUS_DATA),
32017 FOLLOW_TARGET(FOLLOW_TARGET_DATA),
32018 VICON_POSITION_ESTIMATE(VICON_POSITION_ESTIMATE_DATA),
32019 ADSB_VEHICLE(ADSB_VEHICLE_DATA),
32020 GIMBAL_DEVICE_INFORMATION(GIMBAL_DEVICE_INFORMATION_DATA),
32021 UAVIONIX_ADSB_OUT_CFG_REGISTRATION(UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA),
32022 SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA),
32023 ESC_STATUS(ESC_STATUS_DATA),
32024 COLLISION(COLLISION_DATA),
32025 LOGGING_DATA(LOGGING_DATA_DATA),
32026 GPS_INPUT(GPS_INPUT_DATA),
32027 HOME_POSITION(HOME_POSITION_DATA),
32028 PARAM_EXT_REQUEST_READ(PARAM_EXT_REQUEST_READ_DATA),
32029 LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA),
32030 ACTUATOR_OUTPUT_STATUS(ACTUATOR_OUTPUT_STATUS_DATA),
32031 OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA),
32032 WIND_COV(WIND_COV_DATA),
32033 UAVIONIX_ADSB_OUT_DYNAMIC(UAVIONIX_ADSB_OUT_DYNAMIC_DATA),
32034 UAVIONIX_ADSB_OUT_STATUS(UAVIONIX_ADSB_OUT_STATUS_DATA),
32035 HIGH_LATENCY2(HIGH_LATENCY2_DATA),
32036 GIMBAL_DEVICE_SET_ATTITUDE(GIMBAL_DEVICE_SET_ATTITUDE_DATA),
32037 PARAM_EXT_ACK(PARAM_EXT_ACK_DATA),
32038 SAFETY_SET_ALLOWED_AREA(SAFETY_SET_ALLOWED_AREA_DATA),
32039 FENCE_STATUS(FENCE_STATUS_DATA),
32040 WINCH_STATUS(WINCH_STATUS_DATA),
32041 ESC_INFO(ESC_INFO_DATA),
32042 MISSION_REQUEST_PARTIAL_LIST(MISSION_REQUEST_PARTIAL_LIST_DATA),
32043 NAV_CONTROLLER_OUTPUT(NAV_CONTROLLER_OUTPUT_DATA),
32044 HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA),
32045 LOG_DATA(LOG_DATA_DATA),
32046 HIL_STATE_QUATERNION(HIL_STATE_QUATERNION_DATA),
32047 CURRENT_MODE(CURRENT_MODE_DATA),
32048 WHEEL_DISTANCE(WHEEL_DISTANCE_DATA),
32049 OPTICAL_FLOW(OPTICAL_FLOW_DATA),
32050 CHANGE_OPERATOR_CONTROL(CHANGE_OPERATOR_CONTROL_DATA),
32051 VIBRATION(VIBRATION_DATA),
32052 CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA),
32053 MISSION_COUNT(MISSION_COUNT_DATA),
32054 OPEN_DRONE_ID_SYSTEM(OPEN_DRONE_ID_SYSTEM_DATA),
32055 ATTITUDE_QUATERNION_COV(ATTITUDE_QUATERNION_COV_DATA),
32056 POSITION_TARGET_GLOBAL_INT(POSITION_TARGET_GLOBAL_INT_DATA),
32057 SET_ACTUATOR_CONTROL_TARGET(SET_ACTUATOR_CONTROL_TARGET_DATA),
32058 CELLULAR_STATUS(CELLULAR_STATUS_DATA),
32059 COMPONENT_INFORMATION(COMPONENT_INFORMATION_DATA),
32060 RADIO_STATUS(RADIO_STATUS_DATA),
32061 TIMESYNC(TIMESYNC_DATA),
32062 GIMBAL_MANAGER_STATUS(GIMBAL_MANAGER_STATUS_DATA),
32063 COMMAND_CANCEL(COMMAND_CANCEL_DATA),
32064 HIL_ACTUATOR_CONTROLS(HIL_ACTUATOR_CONTROLS_DATA),
32065 NAMED_VALUE_INT(NAMED_VALUE_INT_DATA),
32066 DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA),
32067 OPEN_DRONE_ID_BASIC_ID(OPEN_DRONE_ID_BASIC_ID_DATA),
32068 COMPONENT_METADATA(COMPONENT_METADATA_DATA),
32069 LINK_NODE_STATUS(LINK_NODE_STATUS_DATA),
32070 LOCAL_POSITION_NED_COV(LOCAL_POSITION_NED_COV_DATA),
32071 CANFD_FRAME(CANFD_FRAME_DATA),
32072 OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA),
32073 PLAY_TUNE(PLAY_TUNE_DATA),
32074 COMPONENT_INFORMATION_BASIC(COMPONENT_INFORMATION_BASIC_DATA),
32075 OPEN_DRONE_ID_SELF_ID(OPEN_DRONE_ID_SELF_ID_DATA),
32076 HEARTBEAT(HEARTBEAT_DATA),
32077 EVENT(EVENT_DATA),
32078 OPEN_DRONE_ID_OPERATOR_ID(OPEN_DRONE_ID_OPERATOR_ID_DATA),
32079 AVAILABLE_MODES(AVAILABLE_MODES_DATA),
32080 SET_HOME_POSITION(SET_HOME_POSITION_DATA),
32081 FUEL_STATUS(FUEL_STATUS_DATA),
32082 OPEN_DRONE_ID_MESSAGE_PACK(OPEN_DRONE_ID_MESSAGE_PACK_DATA),
32083 COMMAND_LONG(COMMAND_LONG_DATA),
32084 GPS_RTK(GPS_RTK_DATA),
32085 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA),
32086 CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA),
32087 EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA),
32088 UAVIONIX_ADSB_GET(UAVIONIX_ADSB_GET_DATA),
32089 SUPPORTED_TUNES(SUPPORTED_TUNES_DATA),
32090 DATA_TRANSMISSION_HANDSHAKE(DATA_TRANSMISSION_HANDSHAKE_DATA),
32091 PARAM_EXT_SET(PARAM_EXT_SET_DATA),
32092 CAMERA_IMAGE_CAPTURED(CAMERA_IMAGE_CAPTURED_DATA),
32093 REQUEST_EVENT(REQUEST_EVENT_DATA),
32094 GLOBAL_POSITION_INT_COV(GLOBAL_POSITION_INT_COV_DATA),
32095 PARAM_VALUE(PARAM_VALUE_DATA),
32096 MAG_CAL_REPORT(MAG_CAL_REPORT_DATA),
32097 MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA),
32098 PARAM_MAP_RC(PARAM_MAP_RC_DATA),
32099 STATUSTEXT(STATUSTEXT_DATA),
32100 CAMERA_TRACKING_GEO_STATUS(CAMERA_TRACKING_GEO_STATUS_DATA),
32101 GPS_INJECT_DATA(GPS_INJECT_DATA_DATA),
32102 VFR_HUD(VFR_HUD_DATA),
32103 MISSION_ITEM_INT(MISSION_ITEM_INT_DATA),
32104 ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA),
32105 PLAY_TUNE_V2(PLAY_TUNE_V2_DATA),
32106 CAMERA_SETTINGS(CAMERA_SETTINGS_DATA),
32107 MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA),
32108 MANUAL_SETPOINT(MANUAL_SETPOINT_DATA),
32109 MISSION_SET_CURRENT(MISSION_SET_CURRENT_DATA),
32110 HIL_GPS(HIL_GPS_DATA),
32111 REQUEST_DATA_STREAM(REQUEST_DATA_STREAM_DATA),
32112 HIGH_LATENCY(HIGH_LATENCY_DATA),
32113 FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA),
32114 SERIAL_CONTROL(SERIAL_CONTROL_DATA),
32115 COMMAND_INT(COMMAND_INT_DATA),
32116 CAMERA_INFORMATION(CAMERA_INFORMATION_DATA),
32117 SIM_STATE(SIM_STATE_DATA),
32118 GPS2_RTK(GPS2_RTK_DATA),
32119 SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA),
32120 AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA),
32121 UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA),
32122 RAW_PRESSURE(RAW_PRESSURE_DATA),
32123 VIDEO_STREAM_STATUS(VIDEO_STREAM_STATUS_DATA),
32124 BUTTON_CHANGE(BUTTON_CHANGE_DATA),
32125 PROTOCOL_VERSION(PROTOCOL_VERSION_DATA),
32126 DISTANCE_SENSOR(DISTANCE_SENSOR_DATA),
32127 GIMBAL_MANAGER_SET_ATTITUDE(GIMBAL_MANAGER_SET_ATTITUDE_DATA),
32128 RC_CHANNELS(RC_CHANNELS_DATA),
32129 OPEN_DRONE_ID_SYSTEM_UPDATE(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA),
32130 ATTITUDE_QUATERNION(ATTITUDE_QUATERNION_DATA),
32131 PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA),
32132 SCALED_PRESSURE3(SCALED_PRESSURE3_DATA),
32133 GIMBAL_MANAGER_INFORMATION(GIMBAL_MANAGER_INFORMATION_DATA),
32134 SETUP_SIGNING(SETUP_SIGNING_DATA),
32135 LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA),
32136 UAVIONIX_ADSB_OUT_CONTROL(UAVIONIX_ADSB_OUT_CONTROL_DATA),
32137 MISSION_ITEM_REACHED(MISSION_ITEM_REACHED_DATA),
32138 SET_POSITION_TARGET_GLOBAL_INT(SET_POSITION_TARGET_GLOBAL_INT_DATA),
32139 RESPONSE_EVENT_ERROR(RESPONSE_EVENT_ERROR_DATA),
32140 CURRENT_EVENT_SEQUENCE(CURRENT_EVENT_SEQUENCE_DATA),
32141 CAN_FRAME(CAN_FRAME_DATA),
32142 MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA),
32143 ILLUMINATOR_STATUS(ILLUMINATOR_STATUS_DATA),
32144 CHANGE_OPERATOR_CONTROL_ACK(CHANGE_OPERATOR_CONTROL_ACK_DATA),
32145 GIMBAL_MANAGER_SET_PITCHYAW(GIMBAL_MANAGER_SET_PITCHYAW_DATA),
32146 OPEN_DRONE_ID_ARM_STATUS(OPEN_DRONE_ID_ARM_STATUS_DATA),
32147 UTM_GLOBAL_POSITION(UTM_GLOBAL_POSITION_DATA),
32148 RC_CHANNELS_OVERRIDE(RC_CHANNELS_OVERRIDE_DATA),
32149 SCALED_IMU(SCALED_IMU_DATA),
32150 DATA_STREAM(DATA_STREAM_DATA),
32151 LOG_ENTRY(LOG_ENTRY_DATA),
32152 PING(PING_DATA),
32153 POSITION_TARGET_LOCAL_NED(POSITION_TARGET_LOCAL_NED_DATA),
32154 SCALED_IMU2(SCALED_IMU2_DATA),
32155 GPS_RTCM_DATA(GPS_RTCM_DATA_DATA),
32156 SET_MODE(SET_MODE_DATA),
32157 ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA),
32158 HIL_STATE(HIL_STATE_DATA),
32159 SYSTEM_TIME(SYSTEM_TIME_DATA),
32160 STORAGE_INFORMATION(STORAGE_INFORMATION_DATA),
32161 BATTERY_INFO(BATTERY_INFO_DATA),
32162 SET_ATTITUDE_TARGET(SET_ATTITUDE_TARGET_DATA),
32163 HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA),
32164 CAMERA_TRIGGER(CAMERA_TRIGGER_DATA),
32165 TIME_ESTIMATE_TO_TARGET(TIME_ESTIMATE_TO_TARGET_DATA),
32166 HIL_SENSOR(HIL_SENSOR_DATA),
32167 MISSION_REQUEST_INT(MISSION_REQUEST_INT_DATA),
32168 TERRAIN_REPORT(TERRAIN_REPORT_DATA),
32169 BATTERY_STATUS(BATTERY_STATUS_DATA),
32170 GPS_RAW_INT(GPS_RAW_INT_DATA),
32171 VISION_POSITION_ESTIMATE(VISION_POSITION_ESTIMATE_DATA),
32172 CELLULAR_CONFIG(CELLULAR_CONFIG_DATA),
32173 SET_POSITION_TARGET_LOCAL_NED(SET_POSITION_TARGET_LOCAL_NED_DATA),
32174 GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA),
32175 RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA),
32176 ATTITUDE(ATTITUDE_DATA),
32177 GPS_STATUS(GPS_STATUS_DATA),
32178 CONTROL_SYSTEM_STATE(CONTROL_SYSTEM_STATE_DATA),
32179 PARAM_EXT_REQUEST_LIST(PARAM_EXT_REQUEST_LIST_DATA),
32180 VIDEO_STREAM_INFORMATION(VIDEO_STREAM_INFORMATION_DATA),
32181 RESOURCE_REQUEST(RESOURCE_REQUEST_DATA),
32182 HIGHRES_IMU(HIGHRES_IMU_DATA),
32183 HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA),
32184 MISSION_CURRENT(MISSION_CURRENT_DATA),
32185 AVAILABLE_MODES_MONITOR(AVAILABLE_MODES_MONITOR_DATA),
32186 POWER_STATUS(POWER_STATUS_DATA),
32187 RAW_RPM(RAW_RPM_DATA),
32188 GIMBAL_MANAGER_SET_MANUAL_CONTROL(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA),
32189 UAVIONIX_ADSB_OUT_CFG_FLIGHTID(UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA),
32190 LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA),
32191 RAW_IMU(RAW_IMU_DATA),
32192 PARAM_SET(PARAM_SET_DATA),
32193 MISSION_REQUEST(MISSION_REQUEST_DATA),
32194 SAFETY_ALLOWED_AREA(SAFETY_ALLOWED_AREA_DATA),
32195 GIMBAL_DEVICE_ATTITUDE_STATUS(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA),
32196 GLOBAL_POSITION_INT(GLOBAL_POSITION_INT_DATA),
32197 GLOBAL_VISION_POSITION_ESTIMATE(GLOBAL_VISION_POSITION_ESTIMATE_DATA),
32198 TUNNEL(TUNNEL_DATA),
32199 PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA),
32200 TERRAIN_CHECK(TERRAIN_CHECK_DATA),
32201 COMMAND_ACK(COMMAND_ACK_DATA),
32202 MISSION_ITEM(MISSION_ITEM_DATA),
32203 TRAJECTORY_REPRESENTATION_WAYPOINTS(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA),
32204 DEBUG(DEBUG_DATA),
32205 GPS2_RAW(GPS2_RAW_DATA),
32206 ONBOARD_COMPUTER_STATUS(ONBOARD_COMPUTER_STATUS_DATA),
32207 ATTITUDE_TARGET(ATTITUDE_TARGET_DATA),
32208 RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA),
32209 ODOMETRY(ODOMETRY_DATA),
32210 VISION_SPEED_ESTIMATE(VISION_SPEED_ESTIMATE_DATA),
32211 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA),
32212 ALTITUDE(ALTITUDE_DATA),
32213 OPEN_DRONE_ID_AUTHENTICATION(OPEN_DRONE_ID_AUTHENTICATION_DATA),
32214 PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA),
32215 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA),
32216}
32217impl MavMessage {
32218 pub const fn all_ids() -> &'static [u32] {
32219 &[
32220 0u32, 1u32, 2u32, 4u32, 5u32, 6u32, 7u32, 8u32, 11u32, 20u32, 21u32, 22u32, 23u32,
32221 24u32, 25u32, 26u32, 27u32, 28u32, 29u32, 30u32, 31u32, 32u32, 33u32, 34u32, 35u32,
32222 36u32, 37u32, 38u32, 39u32, 40u32, 41u32, 42u32, 43u32, 44u32, 45u32, 46u32, 47u32,
32223 48u32, 49u32, 50u32, 51u32, 54u32, 55u32, 61u32, 62u32, 63u32, 64u32, 65u32, 66u32,
32224 67u32, 69u32, 70u32, 73u32, 74u32, 75u32, 76u32, 77u32, 80u32, 81u32, 82u32, 83u32,
32225 84u32, 85u32, 86u32, 87u32, 89u32, 90u32, 91u32, 92u32, 93u32, 100u32, 101u32, 102u32,
32226 103u32, 104u32, 105u32, 106u32, 107u32, 108u32, 109u32, 110u32, 111u32, 112u32, 113u32,
32227 114u32, 115u32, 116u32, 117u32, 118u32, 119u32, 120u32, 121u32, 122u32, 123u32, 124u32,
32228 125u32, 126u32, 127u32, 128u32, 129u32, 130u32, 131u32, 132u32, 133u32, 134u32, 135u32,
32229 136u32, 137u32, 138u32, 139u32, 140u32, 141u32, 142u32, 143u32, 144u32, 146u32, 147u32,
32230 148u32, 149u32, 162u32, 192u32, 225u32, 230u32, 231u32, 232u32, 233u32, 234u32, 235u32,
32231 241u32, 242u32, 243u32, 244u32, 245u32, 246u32, 247u32, 248u32, 249u32, 250u32, 251u32,
32232 252u32, 253u32, 254u32, 256u32, 257u32, 258u32, 259u32, 260u32, 261u32, 262u32, 263u32,
32233 264u32, 265u32, 266u32, 267u32, 268u32, 269u32, 270u32, 271u32, 275u32, 276u32, 277u32,
32234 280u32, 281u32, 282u32, 283u32, 284u32, 285u32, 286u32, 287u32, 288u32, 290u32, 291u32,
32235 299u32, 300u32, 301u32, 310u32, 311u32, 320u32, 321u32, 322u32, 323u32, 324u32, 330u32,
32236 331u32, 332u32, 333u32, 334u32, 335u32, 336u32, 339u32, 340u32, 350u32, 360u32, 370u32,
32237 371u32, 372u32, 373u32, 375u32, 380u32, 385u32, 386u32, 387u32, 388u32, 390u32, 395u32,
32238 396u32, 397u32, 400u32, 401u32, 410u32, 411u32, 412u32, 413u32, 435u32, 436u32, 437u32,
32239 440u32, 9000u32, 9005u32, 10001u32, 10002u32, 10003u32, 10004u32, 10005u32, 10006u32,
32240 10007u32, 10008u32, 12900u32, 12901u32, 12902u32, 12903u32, 12904u32, 12905u32,
32241 12915u32, 12918u32, 12919u32, 12920u32,
32242 ]
32243 }
32244}
32245impl Message for MavMessage {
32246 fn parse(
32247 version: MavlinkVersion,
32248 id: u32,
32249 payload: &[u8],
32250 ) -> Result<Self, ::mavlink_core::error::ParserError> {
32251 match id {
32252 ACTUATOR_CONTROL_TARGET_DATA::ID => {
32253 ACTUATOR_CONTROL_TARGET_DATA::deser(version, payload)
32254 .map(Self::ACTUATOR_CONTROL_TARGET)
32255 }
32256 LOG_ERASE_DATA::ID => LOG_ERASE_DATA::deser(version, payload).map(Self::LOG_ERASE),
32257 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => {
32258 CAMERA_TRACKING_IMAGE_STATUS_DATA::deser(version, payload)
32259 .map(Self::CAMERA_TRACKING_IMAGE_STATUS)
32260 }
32261 MISSION_WRITE_PARTIAL_LIST_DATA::ID => {
32262 MISSION_WRITE_PARTIAL_LIST_DATA::deser(version, payload)
32263 .map(Self::MISSION_WRITE_PARTIAL_LIST)
32264 }
32265 SCALED_PRESSURE_DATA::ID => {
32266 SCALED_PRESSURE_DATA::deser(version, payload).map(Self::SCALED_PRESSURE)
32267 }
32268 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
32269 TRAJECTORY_REPRESENTATION_BEZIER_DATA::deser(version, payload)
32270 .map(Self::TRAJECTORY_REPRESENTATION_BEZIER)
32271 }
32272 ORBIT_EXECUTION_STATUS_DATA::ID => ORBIT_EXECUTION_STATUS_DATA::deser(version, payload)
32273 .map(Self::ORBIT_EXECUTION_STATUS),
32274 AUTH_KEY_DATA::ID => AUTH_KEY_DATA::deser(version, payload).map(Self::AUTH_KEY),
32275 FILE_TRANSFER_PROTOCOL_DATA::ID => FILE_TRANSFER_PROTOCOL_DATA::deser(version, payload)
32276 .map(Self::FILE_TRANSFER_PROTOCOL),
32277 SYS_STATUS_DATA::ID => SYS_STATUS_DATA::deser(version, payload).map(Self::SYS_STATUS),
32278 LOG_REQUEST_END_DATA::ID => {
32279 LOG_REQUEST_END_DATA::deser(version, payload).map(Self::LOG_REQUEST_END)
32280 }
32281 TERRAIN_DATA_DATA::ID => {
32282 TERRAIN_DATA_DATA::deser(version, payload).map(Self::TERRAIN_DATA)
32283 }
32284 LOGGING_DATA_ACKED_DATA::ID => {
32285 LOGGING_DATA_ACKED_DATA::deser(version, payload).map(Self::LOGGING_DATA_ACKED)
32286 }
32287 NAMED_VALUE_FLOAT_DATA::ID => {
32288 NAMED_VALUE_FLOAT_DATA::deser(version, payload).map(Self::NAMED_VALUE_FLOAT)
32289 }
32290 LANDING_TARGET_DATA::ID => {
32291 LANDING_TARGET_DATA::deser(version, payload).map(Self::LANDING_TARGET)
32292 }
32293 ATT_POS_MOCAP_DATA::ID => {
32294 ATT_POS_MOCAP_DATA::deser(version, payload).map(Self::ATT_POS_MOCAP)
32295 }
32296 SCALED_IMU3_DATA::ID => {
32297 SCALED_IMU3_DATA::deser(version, payload).map(Self::SCALED_IMU3)
32298 }
32299 MEMORY_VECT_DATA::ID => {
32300 MEMORY_VECT_DATA::deser(version, payload).map(Self::MEMORY_VECT)
32301 }
32302 TERRAIN_REQUEST_DATA::ID => {
32303 TERRAIN_REQUEST_DATA::deser(version, payload).map(Self::TERRAIN_REQUEST)
32304 }
32305 V2_EXTENSION_DATA::ID => {
32306 V2_EXTENSION_DATA::deser(version, payload).map(Self::V2_EXTENSION)
32307 }
32308 DEBUG_VECT_DATA::ID => DEBUG_VECT_DATA::deser(version, payload).map(Self::DEBUG_VECT),
32309 MANUAL_CONTROL_DATA::ID => {
32310 MANUAL_CONTROL_DATA::deser(version, payload).map(Self::MANUAL_CONTROL)
32311 }
32312 AIS_VESSEL_DATA::ID => AIS_VESSEL_DATA::deser(version, payload).map(Self::AIS_VESSEL),
32313 UAVCAN_NODE_INFO_DATA::ID => {
32314 UAVCAN_NODE_INFO_DATA::deser(version, payload).map(Self::UAVCAN_NODE_INFO)
32315 }
32316 SET_GPS_GLOBAL_ORIGIN_DATA::ID => {
32317 SET_GPS_GLOBAL_ORIGIN_DATA::deser(version, payload).map(Self::SET_GPS_GLOBAL_ORIGIN)
32318 }
32319 SCALED_PRESSURE2_DATA::ID => {
32320 SCALED_PRESSURE2_DATA::deser(version, payload).map(Self::SCALED_PRESSURE2)
32321 }
32322 CAMERA_CAPTURE_STATUS_DATA::ID => {
32323 CAMERA_CAPTURE_STATUS_DATA::deser(version, payload).map(Self::CAMERA_CAPTURE_STATUS)
32324 }
32325 WIFI_CONFIG_AP_DATA::ID => {
32326 WIFI_CONFIG_AP_DATA::deser(version, payload).map(Self::WIFI_CONFIG_AP)
32327 }
32328 MISSION_REQUEST_LIST_DATA::ID => {
32329 MISSION_REQUEST_LIST_DATA::deser(version, payload).map(Self::MISSION_REQUEST_LIST)
32330 }
32331 MISSION_ACK_DATA::ID => {
32332 MISSION_ACK_DATA::deser(version, payload).map(Self::MISSION_ACK)
32333 }
32334 ENCAPSULATED_DATA_DATA::ID => {
32335 ENCAPSULATED_DATA_DATA::deser(version, payload).map(Self::ENCAPSULATED_DATA)
32336 }
32337 UAVIONIX_ADSB_OUT_CFG_DATA::ID => {
32338 UAVIONIX_ADSB_OUT_CFG_DATA::deser(version, payload).map(Self::UAVIONIX_ADSB_OUT_CFG)
32339 }
32340 EFI_STATUS_DATA::ID => EFI_STATUS_DATA::deser(version, payload).map(Self::EFI_STATUS),
32341 OPEN_DRONE_ID_LOCATION_DATA::ID => OPEN_DRONE_ID_LOCATION_DATA::deser(version, payload)
32342 .map(Self::OPEN_DRONE_ID_LOCATION),
32343 CAMERA_THERMAL_RANGE_DATA::ID => {
32344 CAMERA_THERMAL_RANGE_DATA::deser(version, payload).map(Self::CAMERA_THERMAL_RANGE)
32345 }
32346 LOGGING_ACK_DATA::ID => {
32347 LOGGING_ACK_DATA::deser(version, payload).map(Self::LOGGING_ACK)
32348 }
32349 HIL_CONTROLS_DATA::ID => {
32350 HIL_CONTROLS_DATA::deser(version, payload).map(Self::HIL_CONTROLS)
32351 }
32352 GENERATOR_STATUS_DATA::ID => {
32353 GENERATOR_STATUS_DATA::deser(version, payload).map(Self::GENERATOR_STATUS)
32354 }
32355 FOLLOW_TARGET_DATA::ID => {
32356 FOLLOW_TARGET_DATA::deser(version, payload).map(Self::FOLLOW_TARGET)
32357 }
32358 VICON_POSITION_ESTIMATE_DATA::ID => {
32359 VICON_POSITION_ESTIMATE_DATA::deser(version, payload)
32360 .map(Self::VICON_POSITION_ESTIMATE)
32361 }
32362 ADSB_VEHICLE_DATA::ID => {
32363 ADSB_VEHICLE_DATA::deser(version, payload).map(Self::ADSB_VEHICLE)
32364 }
32365 GIMBAL_DEVICE_INFORMATION_DATA::ID => {
32366 GIMBAL_DEVICE_INFORMATION_DATA::deser(version, payload)
32367 .map(Self::GIMBAL_DEVICE_INFORMATION)
32368 }
32369 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID => {
32370 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::deser(version, payload)
32371 .map(Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION)
32372 }
32373 SMART_BATTERY_INFO_DATA::ID => {
32374 SMART_BATTERY_INFO_DATA::deser(version, payload).map(Self::SMART_BATTERY_INFO)
32375 }
32376 ESC_STATUS_DATA::ID => ESC_STATUS_DATA::deser(version, payload).map(Self::ESC_STATUS),
32377 COLLISION_DATA::ID => COLLISION_DATA::deser(version, payload).map(Self::COLLISION),
32378 LOGGING_DATA_DATA::ID => {
32379 LOGGING_DATA_DATA::deser(version, payload).map(Self::LOGGING_DATA)
32380 }
32381 GPS_INPUT_DATA::ID => GPS_INPUT_DATA::deser(version, payload).map(Self::GPS_INPUT),
32382 HOME_POSITION_DATA::ID => {
32383 HOME_POSITION_DATA::deser(version, payload).map(Self::HOME_POSITION)
32384 }
32385 PARAM_EXT_REQUEST_READ_DATA::ID => PARAM_EXT_REQUEST_READ_DATA::deser(version, payload)
32386 .map(Self::PARAM_EXT_REQUEST_READ),
32387 LOG_REQUEST_LIST_DATA::ID => {
32388 LOG_REQUEST_LIST_DATA::deser(version, payload).map(Self::LOG_REQUEST_LIST)
32389 }
32390 ACTUATOR_OUTPUT_STATUS_DATA::ID => ACTUATOR_OUTPUT_STATUS_DATA::deser(version, payload)
32391 .map(Self::ACTUATOR_OUTPUT_STATUS),
32392 OBSTACLE_DISTANCE_DATA::ID => {
32393 OBSTACLE_DISTANCE_DATA::deser(version, payload).map(Self::OBSTACLE_DISTANCE)
32394 }
32395 WIND_COV_DATA::ID => WIND_COV_DATA::deser(version, payload).map(Self::WIND_COV),
32396 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID => {
32397 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::deser(version, payload)
32398 .map(Self::UAVIONIX_ADSB_OUT_DYNAMIC)
32399 }
32400 UAVIONIX_ADSB_OUT_STATUS_DATA::ID => {
32401 UAVIONIX_ADSB_OUT_STATUS_DATA::deser(version, payload)
32402 .map(Self::UAVIONIX_ADSB_OUT_STATUS)
32403 }
32404 HIGH_LATENCY2_DATA::ID => {
32405 HIGH_LATENCY2_DATA::deser(version, payload).map(Self::HIGH_LATENCY2)
32406 }
32407 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => {
32408 GIMBAL_DEVICE_SET_ATTITUDE_DATA::deser(version, payload)
32409 .map(Self::GIMBAL_DEVICE_SET_ATTITUDE)
32410 }
32411 PARAM_EXT_ACK_DATA::ID => {
32412 PARAM_EXT_ACK_DATA::deser(version, payload).map(Self::PARAM_EXT_ACK)
32413 }
32414 SAFETY_SET_ALLOWED_AREA_DATA::ID => {
32415 SAFETY_SET_ALLOWED_AREA_DATA::deser(version, payload)
32416 .map(Self::SAFETY_SET_ALLOWED_AREA)
32417 }
32418 FENCE_STATUS_DATA::ID => {
32419 FENCE_STATUS_DATA::deser(version, payload).map(Self::FENCE_STATUS)
32420 }
32421 WINCH_STATUS_DATA::ID => {
32422 WINCH_STATUS_DATA::deser(version, payload).map(Self::WINCH_STATUS)
32423 }
32424 ESC_INFO_DATA::ID => ESC_INFO_DATA::deser(version, payload).map(Self::ESC_INFO),
32425 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => {
32426 MISSION_REQUEST_PARTIAL_LIST_DATA::deser(version, payload)
32427 .map(Self::MISSION_REQUEST_PARTIAL_LIST)
32428 }
32429 NAV_CONTROLLER_OUTPUT_DATA::ID => {
32430 NAV_CONTROLLER_OUTPUT_DATA::deser(version, payload).map(Self::NAV_CONTROLLER_OUTPUT)
32431 }
32432 HIL_OPTICAL_FLOW_DATA::ID => {
32433 HIL_OPTICAL_FLOW_DATA::deser(version, payload).map(Self::HIL_OPTICAL_FLOW)
32434 }
32435 LOG_DATA_DATA::ID => LOG_DATA_DATA::deser(version, payload).map(Self::LOG_DATA),
32436 HIL_STATE_QUATERNION_DATA::ID => {
32437 HIL_STATE_QUATERNION_DATA::deser(version, payload).map(Self::HIL_STATE_QUATERNION)
32438 }
32439 CURRENT_MODE_DATA::ID => {
32440 CURRENT_MODE_DATA::deser(version, payload).map(Self::CURRENT_MODE)
32441 }
32442 WHEEL_DISTANCE_DATA::ID => {
32443 WHEEL_DISTANCE_DATA::deser(version, payload).map(Self::WHEEL_DISTANCE)
32444 }
32445 OPTICAL_FLOW_DATA::ID => {
32446 OPTICAL_FLOW_DATA::deser(version, payload).map(Self::OPTICAL_FLOW)
32447 }
32448 CHANGE_OPERATOR_CONTROL_DATA::ID => {
32449 CHANGE_OPERATOR_CONTROL_DATA::deser(version, payload)
32450 .map(Self::CHANGE_OPERATOR_CONTROL)
32451 }
32452 VIBRATION_DATA::ID => VIBRATION_DATA::deser(version, payload).map(Self::VIBRATION),
32453 CAMERA_FOV_STATUS_DATA::ID => {
32454 CAMERA_FOV_STATUS_DATA::deser(version, payload).map(Self::CAMERA_FOV_STATUS)
32455 }
32456 MISSION_COUNT_DATA::ID => {
32457 MISSION_COUNT_DATA::deser(version, payload).map(Self::MISSION_COUNT)
32458 }
32459 OPEN_DRONE_ID_SYSTEM_DATA::ID => {
32460 OPEN_DRONE_ID_SYSTEM_DATA::deser(version, payload).map(Self::OPEN_DRONE_ID_SYSTEM)
32461 }
32462 ATTITUDE_QUATERNION_COV_DATA::ID => {
32463 ATTITUDE_QUATERNION_COV_DATA::deser(version, payload)
32464 .map(Self::ATTITUDE_QUATERNION_COV)
32465 }
32466 POSITION_TARGET_GLOBAL_INT_DATA::ID => {
32467 POSITION_TARGET_GLOBAL_INT_DATA::deser(version, payload)
32468 .map(Self::POSITION_TARGET_GLOBAL_INT)
32469 }
32470 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => {
32471 SET_ACTUATOR_CONTROL_TARGET_DATA::deser(version, payload)
32472 .map(Self::SET_ACTUATOR_CONTROL_TARGET)
32473 }
32474 CELLULAR_STATUS_DATA::ID => {
32475 CELLULAR_STATUS_DATA::deser(version, payload).map(Self::CELLULAR_STATUS)
32476 }
32477 COMPONENT_INFORMATION_DATA::ID => {
32478 COMPONENT_INFORMATION_DATA::deser(version, payload).map(Self::COMPONENT_INFORMATION)
32479 }
32480 RADIO_STATUS_DATA::ID => {
32481 RADIO_STATUS_DATA::deser(version, payload).map(Self::RADIO_STATUS)
32482 }
32483 TIMESYNC_DATA::ID => TIMESYNC_DATA::deser(version, payload).map(Self::TIMESYNC),
32484 GIMBAL_MANAGER_STATUS_DATA::ID => {
32485 GIMBAL_MANAGER_STATUS_DATA::deser(version, payload).map(Self::GIMBAL_MANAGER_STATUS)
32486 }
32487 COMMAND_CANCEL_DATA::ID => {
32488 COMMAND_CANCEL_DATA::deser(version, payload).map(Self::COMMAND_CANCEL)
32489 }
32490 HIL_ACTUATOR_CONTROLS_DATA::ID => {
32491 HIL_ACTUATOR_CONTROLS_DATA::deser(version, payload).map(Self::HIL_ACTUATOR_CONTROLS)
32492 }
32493 NAMED_VALUE_INT_DATA::ID => {
32494 NAMED_VALUE_INT_DATA::deser(version, payload).map(Self::NAMED_VALUE_INT)
32495 }
32496 DEBUG_FLOAT_ARRAY_DATA::ID => {
32497 DEBUG_FLOAT_ARRAY_DATA::deser(version, payload).map(Self::DEBUG_FLOAT_ARRAY)
32498 }
32499 OPEN_DRONE_ID_BASIC_ID_DATA::ID => OPEN_DRONE_ID_BASIC_ID_DATA::deser(version, payload)
32500 .map(Self::OPEN_DRONE_ID_BASIC_ID),
32501 COMPONENT_METADATA_DATA::ID => {
32502 COMPONENT_METADATA_DATA::deser(version, payload).map(Self::COMPONENT_METADATA)
32503 }
32504 LINK_NODE_STATUS_DATA::ID => {
32505 LINK_NODE_STATUS_DATA::deser(version, payload).map(Self::LINK_NODE_STATUS)
32506 }
32507 LOCAL_POSITION_NED_COV_DATA::ID => LOCAL_POSITION_NED_COV_DATA::deser(version, payload)
32508 .map(Self::LOCAL_POSITION_NED_COV),
32509 CANFD_FRAME_DATA::ID => {
32510 CANFD_FRAME_DATA::deser(version, payload).map(Self::CANFD_FRAME)
32511 }
32512 OPTICAL_FLOW_RAD_DATA::ID => {
32513 OPTICAL_FLOW_RAD_DATA::deser(version, payload).map(Self::OPTICAL_FLOW_RAD)
32514 }
32515 PLAY_TUNE_DATA::ID => PLAY_TUNE_DATA::deser(version, payload).map(Self::PLAY_TUNE),
32516 COMPONENT_INFORMATION_BASIC_DATA::ID => {
32517 COMPONENT_INFORMATION_BASIC_DATA::deser(version, payload)
32518 .map(Self::COMPONENT_INFORMATION_BASIC)
32519 }
32520 OPEN_DRONE_ID_SELF_ID_DATA::ID => {
32521 OPEN_DRONE_ID_SELF_ID_DATA::deser(version, payload).map(Self::OPEN_DRONE_ID_SELF_ID)
32522 }
32523 HEARTBEAT_DATA::ID => HEARTBEAT_DATA::deser(version, payload).map(Self::HEARTBEAT),
32524 EVENT_DATA::ID => EVENT_DATA::deser(version, payload).map(Self::EVENT),
32525 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => {
32526 OPEN_DRONE_ID_OPERATOR_ID_DATA::deser(version, payload)
32527 .map(Self::OPEN_DRONE_ID_OPERATOR_ID)
32528 }
32529 AVAILABLE_MODES_DATA::ID => {
32530 AVAILABLE_MODES_DATA::deser(version, payload).map(Self::AVAILABLE_MODES)
32531 }
32532 SET_HOME_POSITION_DATA::ID => {
32533 SET_HOME_POSITION_DATA::deser(version, payload).map(Self::SET_HOME_POSITION)
32534 }
32535 FUEL_STATUS_DATA::ID => {
32536 FUEL_STATUS_DATA::deser(version, payload).map(Self::FUEL_STATUS)
32537 }
32538 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => {
32539 OPEN_DRONE_ID_MESSAGE_PACK_DATA::deser(version, payload)
32540 .map(Self::OPEN_DRONE_ID_MESSAGE_PACK)
32541 }
32542 COMMAND_LONG_DATA::ID => {
32543 COMMAND_LONG_DATA::deser(version, payload).map(Self::COMMAND_LONG)
32544 }
32545 GPS_RTK_DATA::ID => GPS_RTK_DATA::deser(version, payload).map(Self::GPS_RTK),
32546 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID => {
32547 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::deser(version, payload)
32548 .map(Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT)
32549 }
32550 CAN_FILTER_MODIFY_DATA::ID => {
32551 CAN_FILTER_MODIFY_DATA::deser(version, payload).map(Self::CAN_FILTER_MODIFY)
32552 }
32553 EXTENDED_SYS_STATE_DATA::ID => {
32554 EXTENDED_SYS_STATE_DATA::deser(version, payload).map(Self::EXTENDED_SYS_STATE)
32555 }
32556 UAVIONIX_ADSB_GET_DATA::ID => {
32557 UAVIONIX_ADSB_GET_DATA::deser(version, payload).map(Self::UAVIONIX_ADSB_GET)
32558 }
32559 SUPPORTED_TUNES_DATA::ID => {
32560 SUPPORTED_TUNES_DATA::deser(version, payload).map(Self::SUPPORTED_TUNES)
32561 }
32562 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => {
32563 DATA_TRANSMISSION_HANDSHAKE_DATA::deser(version, payload)
32564 .map(Self::DATA_TRANSMISSION_HANDSHAKE)
32565 }
32566 PARAM_EXT_SET_DATA::ID => {
32567 PARAM_EXT_SET_DATA::deser(version, payload).map(Self::PARAM_EXT_SET)
32568 }
32569 CAMERA_IMAGE_CAPTURED_DATA::ID => {
32570 CAMERA_IMAGE_CAPTURED_DATA::deser(version, payload).map(Self::CAMERA_IMAGE_CAPTURED)
32571 }
32572 REQUEST_EVENT_DATA::ID => {
32573 REQUEST_EVENT_DATA::deser(version, payload).map(Self::REQUEST_EVENT)
32574 }
32575 GLOBAL_POSITION_INT_COV_DATA::ID => {
32576 GLOBAL_POSITION_INT_COV_DATA::deser(version, payload)
32577 .map(Self::GLOBAL_POSITION_INT_COV)
32578 }
32579 PARAM_VALUE_DATA::ID => {
32580 PARAM_VALUE_DATA::deser(version, payload).map(Self::PARAM_VALUE)
32581 }
32582 MAG_CAL_REPORT_DATA::ID => {
32583 MAG_CAL_REPORT_DATA::deser(version, payload).map(Self::MAG_CAL_REPORT)
32584 }
32585 MESSAGE_INTERVAL_DATA::ID => {
32586 MESSAGE_INTERVAL_DATA::deser(version, payload).map(Self::MESSAGE_INTERVAL)
32587 }
32588 PARAM_MAP_RC_DATA::ID => {
32589 PARAM_MAP_RC_DATA::deser(version, payload).map(Self::PARAM_MAP_RC)
32590 }
32591 STATUSTEXT_DATA::ID => STATUSTEXT_DATA::deser(version, payload).map(Self::STATUSTEXT),
32592 CAMERA_TRACKING_GEO_STATUS_DATA::ID => {
32593 CAMERA_TRACKING_GEO_STATUS_DATA::deser(version, payload)
32594 .map(Self::CAMERA_TRACKING_GEO_STATUS)
32595 }
32596 GPS_INJECT_DATA_DATA::ID => {
32597 GPS_INJECT_DATA_DATA::deser(version, payload).map(Self::GPS_INJECT_DATA)
32598 }
32599 VFR_HUD_DATA::ID => VFR_HUD_DATA::deser(version, payload).map(Self::VFR_HUD),
32600 MISSION_ITEM_INT_DATA::ID => {
32601 MISSION_ITEM_INT_DATA::deser(version, payload).map(Self::MISSION_ITEM_INT)
32602 }
32603 ISBD_LINK_STATUS_DATA::ID => {
32604 ISBD_LINK_STATUS_DATA::deser(version, payload).map(Self::ISBD_LINK_STATUS)
32605 }
32606 PLAY_TUNE_V2_DATA::ID => {
32607 PLAY_TUNE_V2_DATA::deser(version, payload).map(Self::PLAY_TUNE_V2)
32608 }
32609 CAMERA_SETTINGS_DATA::ID => {
32610 CAMERA_SETTINGS_DATA::deser(version, payload).map(Self::CAMERA_SETTINGS)
32611 }
32612 MISSION_CLEAR_ALL_DATA::ID => {
32613 MISSION_CLEAR_ALL_DATA::deser(version, payload).map(Self::MISSION_CLEAR_ALL)
32614 }
32615 MANUAL_SETPOINT_DATA::ID => {
32616 MANUAL_SETPOINT_DATA::deser(version, payload).map(Self::MANUAL_SETPOINT)
32617 }
32618 MISSION_SET_CURRENT_DATA::ID => {
32619 MISSION_SET_CURRENT_DATA::deser(version, payload).map(Self::MISSION_SET_CURRENT)
32620 }
32621 HIL_GPS_DATA::ID => HIL_GPS_DATA::deser(version, payload).map(Self::HIL_GPS),
32622 REQUEST_DATA_STREAM_DATA::ID => {
32623 REQUEST_DATA_STREAM_DATA::deser(version, payload).map(Self::REQUEST_DATA_STREAM)
32624 }
32625 HIGH_LATENCY_DATA::ID => {
32626 HIGH_LATENCY_DATA::deser(version, payload).map(Self::HIGH_LATENCY)
32627 }
32628 FLIGHT_INFORMATION_DATA::ID => {
32629 FLIGHT_INFORMATION_DATA::deser(version, payload).map(Self::FLIGHT_INFORMATION)
32630 }
32631 SERIAL_CONTROL_DATA::ID => {
32632 SERIAL_CONTROL_DATA::deser(version, payload).map(Self::SERIAL_CONTROL)
32633 }
32634 COMMAND_INT_DATA::ID => {
32635 COMMAND_INT_DATA::deser(version, payload).map(Self::COMMAND_INT)
32636 }
32637 CAMERA_INFORMATION_DATA::ID => {
32638 CAMERA_INFORMATION_DATA::deser(version, payload).map(Self::CAMERA_INFORMATION)
32639 }
32640 SIM_STATE_DATA::ID => SIM_STATE_DATA::deser(version, payload).map(Self::SIM_STATE),
32641 GPS2_RTK_DATA::ID => GPS2_RTK_DATA::deser(version, payload).map(Self::GPS2_RTK),
32642 SERVO_OUTPUT_RAW_DATA::ID => {
32643 SERVO_OUTPUT_RAW_DATA::deser(version, payload).map(Self::SERVO_OUTPUT_RAW)
32644 }
32645 AUTOPILOT_VERSION_DATA::ID => {
32646 AUTOPILOT_VERSION_DATA::deser(version, payload).map(Self::AUTOPILOT_VERSION)
32647 }
32648 UAVCAN_NODE_STATUS_DATA::ID => {
32649 UAVCAN_NODE_STATUS_DATA::deser(version, payload).map(Self::UAVCAN_NODE_STATUS)
32650 }
32651 RAW_PRESSURE_DATA::ID => {
32652 RAW_PRESSURE_DATA::deser(version, payload).map(Self::RAW_PRESSURE)
32653 }
32654 VIDEO_STREAM_STATUS_DATA::ID => {
32655 VIDEO_STREAM_STATUS_DATA::deser(version, payload).map(Self::VIDEO_STREAM_STATUS)
32656 }
32657 BUTTON_CHANGE_DATA::ID => {
32658 BUTTON_CHANGE_DATA::deser(version, payload).map(Self::BUTTON_CHANGE)
32659 }
32660 PROTOCOL_VERSION_DATA::ID => {
32661 PROTOCOL_VERSION_DATA::deser(version, payload).map(Self::PROTOCOL_VERSION)
32662 }
32663 DISTANCE_SENSOR_DATA::ID => {
32664 DISTANCE_SENSOR_DATA::deser(version, payload).map(Self::DISTANCE_SENSOR)
32665 }
32666 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => {
32667 GIMBAL_MANAGER_SET_ATTITUDE_DATA::deser(version, payload)
32668 .map(Self::GIMBAL_MANAGER_SET_ATTITUDE)
32669 }
32670 RC_CHANNELS_DATA::ID => {
32671 RC_CHANNELS_DATA::deser(version, payload).map(Self::RC_CHANNELS)
32672 }
32673 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => {
32674 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::deser(version, payload)
32675 .map(Self::OPEN_DRONE_ID_SYSTEM_UPDATE)
32676 }
32677 ATTITUDE_QUATERNION_DATA::ID => {
32678 ATTITUDE_QUATERNION_DATA::deser(version, payload).map(Self::ATTITUDE_QUATERNION)
32679 }
32680 PARAM_REQUEST_READ_DATA::ID => {
32681 PARAM_REQUEST_READ_DATA::deser(version, payload).map(Self::PARAM_REQUEST_READ)
32682 }
32683 SCALED_PRESSURE3_DATA::ID => {
32684 SCALED_PRESSURE3_DATA::deser(version, payload).map(Self::SCALED_PRESSURE3)
32685 }
32686 GIMBAL_MANAGER_INFORMATION_DATA::ID => {
32687 GIMBAL_MANAGER_INFORMATION_DATA::deser(version, payload)
32688 .map(Self::GIMBAL_MANAGER_INFORMATION)
32689 }
32690 SETUP_SIGNING_DATA::ID => {
32691 SETUP_SIGNING_DATA::deser(version, payload).map(Self::SETUP_SIGNING)
32692 }
32693 LOG_REQUEST_DATA_DATA::ID => {
32694 LOG_REQUEST_DATA_DATA::deser(version, payload).map(Self::LOG_REQUEST_DATA)
32695 }
32696 UAVIONIX_ADSB_OUT_CONTROL_DATA::ID => {
32697 UAVIONIX_ADSB_OUT_CONTROL_DATA::deser(version, payload)
32698 .map(Self::UAVIONIX_ADSB_OUT_CONTROL)
32699 }
32700 MISSION_ITEM_REACHED_DATA::ID => {
32701 MISSION_ITEM_REACHED_DATA::deser(version, payload).map(Self::MISSION_ITEM_REACHED)
32702 }
32703 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => {
32704 SET_POSITION_TARGET_GLOBAL_INT_DATA::deser(version, payload)
32705 .map(Self::SET_POSITION_TARGET_GLOBAL_INT)
32706 }
32707 RESPONSE_EVENT_ERROR_DATA::ID => {
32708 RESPONSE_EVENT_ERROR_DATA::deser(version, payload).map(Self::RESPONSE_EVENT_ERROR)
32709 }
32710 CURRENT_EVENT_SEQUENCE_DATA::ID => CURRENT_EVENT_SEQUENCE_DATA::deser(version, payload)
32711 .map(Self::CURRENT_EVENT_SEQUENCE),
32712 CAN_FRAME_DATA::ID => CAN_FRAME_DATA::deser(version, payload).map(Self::CAN_FRAME),
32713 MOUNT_ORIENTATION_DATA::ID => {
32714 MOUNT_ORIENTATION_DATA::deser(version, payload).map(Self::MOUNT_ORIENTATION)
32715 }
32716 ILLUMINATOR_STATUS_DATA::ID => {
32717 ILLUMINATOR_STATUS_DATA::deser(version, payload).map(Self::ILLUMINATOR_STATUS)
32718 }
32719 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => {
32720 CHANGE_OPERATOR_CONTROL_ACK_DATA::deser(version, payload)
32721 .map(Self::CHANGE_OPERATOR_CONTROL_ACK)
32722 }
32723 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => {
32724 GIMBAL_MANAGER_SET_PITCHYAW_DATA::deser(version, payload)
32725 .map(Self::GIMBAL_MANAGER_SET_PITCHYAW)
32726 }
32727 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => {
32728 OPEN_DRONE_ID_ARM_STATUS_DATA::deser(version, payload)
32729 .map(Self::OPEN_DRONE_ID_ARM_STATUS)
32730 }
32731 UTM_GLOBAL_POSITION_DATA::ID => {
32732 UTM_GLOBAL_POSITION_DATA::deser(version, payload).map(Self::UTM_GLOBAL_POSITION)
32733 }
32734 RC_CHANNELS_OVERRIDE_DATA::ID => {
32735 RC_CHANNELS_OVERRIDE_DATA::deser(version, payload).map(Self::RC_CHANNELS_OVERRIDE)
32736 }
32737 SCALED_IMU_DATA::ID => SCALED_IMU_DATA::deser(version, payload).map(Self::SCALED_IMU),
32738 DATA_STREAM_DATA::ID => {
32739 DATA_STREAM_DATA::deser(version, payload).map(Self::DATA_STREAM)
32740 }
32741 LOG_ENTRY_DATA::ID => LOG_ENTRY_DATA::deser(version, payload).map(Self::LOG_ENTRY),
32742 PING_DATA::ID => PING_DATA::deser(version, payload).map(Self::PING),
32743 POSITION_TARGET_LOCAL_NED_DATA::ID => {
32744 POSITION_TARGET_LOCAL_NED_DATA::deser(version, payload)
32745 .map(Self::POSITION_TARGET_LOCAL_NED)
32746 }
32747 SCALED_IMU2_DATA::ID => {
32748 SCALED_IMU2_DATA::deser(version, payload).map(Self::SCALED_IMU2)
32749 }
32750 GPS_RTCM_DATA_DATA::ID => {
32751 GPS_RTCM_DATA_DATA::deser(version, payload).map(Self::GPS_RTCM_DATA)
32752 }
32753 SET_MODE_DATA::ID => SET_MODE_DATA::deser(version, payload).map(Self::SET_MODE),
32754 ESTIMATOR_STATUS_DATA::ID => {
32755 ESTIMATOR_STATUS_DATA::deser(version, payload).map(Self::ESTIMATOR_STATUS)
32756 }
32757 HIL_STATE_DATA::ID => HIL_STATE_DATA::deser(version, payload).map(Self::HIL_STATE),
32758 SYSTEM_TIME_DATA::ID => {
32759 SYSTEM_TIME_DATA::deser(version, payload).map(Self::SYSTEM_TIME)
32760 }
32761 STORAGE_INFORMATION_DATA::ID => {
32762 STORAGE_INFORMATION_DATA::deser(version, payload).map(Self::STORAGE_INFORMATION)
32763 }
32764 BATTERY_INFO_DATA::ID => {
32765 BATTERY_INFO_DATA::deser(version, payload).map(Self::BATTERY_INFO)
32766 }
32767 SET_ATTITUDE_TARGET_DATA::ID => {
32768 SET_ATTITUDE_TARGET_DATA::deser(version, payload).map(Self::SET_ATTITUDE_TARGET)
32769 }
32770 HIL_RC_INPUTS_RAW_DATA::ID => {
32771 HIL_RC_INPUTS_RAW_DATA::deser(version, payload).map(Self::HIL_RC_INPUTS_RAW)
32772 }
32773 CAMERA_TRIGGER_DATA::ID => {
32774 CAMERA_TRIGGER_DATA::deser(version, payload).map(Self::CAMERA_TRIGGER)
32775 }
32776 TIME_ESTIMATE_TO_TARGET_DATA::ID => {
32777 TIME_ESTIMATE_TO_TARGET_DATA::deser(version, payload)
32778 .map(Self::TIME_ESTIMATE_TO_TARGET)
32779 }
32780 HIL_SENSOR_DATA::ID => HIL_SENSOR_DATA::deser(version, payload).map(Self::HIL_SENSOR),
32781 MISSION_REQUEST_INT_DATA::ID => {
32782 MISSION_REQUEST_INT_DATA::deser(version, payload).map(Self::MISSION_REQUEST_INT)
32783 }
32784 TERRAIN_REPORT_DATA::ID => {
32785 TERRAIN_REPORT_DATA::deser(version, payload).map(Self::TERRAIN_REPORT)
32786 }
32787 BATTERY_STATUS_DATA::ID => {
32788 BATTERY_STATUS_DATA::deser(version, payload).map(Self::BATTERY_STATUS)
32789 }
32790 GPS_RAW_INT_DATA::ID => {
32791 GPS_RAW_INT_DATA::deser(version, payload).map(Self::GPS_RAW_INT)
32792 }
32793 VISION_POSITION_ESTIMATE_DATA::ID => {
32794 VISION_POSITION_ESTIMATE_DATA::deser(version, payload)
32795 .map(Self::VISION_POSITION_ESTIMATE)
32796 }
32797 CELLULAR_CONFIG_DATA::ID => {
32798 CELLULAR_CONFIG_DATA::deser(version, payload).map(Self::CELLULAR_CONFIG)
32799 }
32800 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => {
32801 SET_POSITION_TARGET_LOCAL_NED_DATA::deser(version, payload)
32802 .map(Self::SET_POSITION_TARGET_LOCAL_NED)
32803 }
32804 GPS_GLOBAL_ORIGIN_DATA::ID => {
32805 GPS_GLOBAL_ORIGIN_DATA::deser(version, payload).map(Self::GPS_GLOBAL_ORIGIN)
32806 }
32807 RC_CHANNELS_SCALED_DATA::ID => {
32808 RC_CHANNELS_SCALED_DATA::deser(version, payload).map(Self::RC_CHANNELS_SCALED)
32809 }
32810 ATTITUDE_DATA::ID => ATTITUDE_DATA::deser(version, payload).map(Self::ATTITUDE),
32811 GPS_STATUS_DATA::ID => GPS_STATUS_DATA::deser(version, payload).map(Self::GPS_STATUS),
32812 CONTROL_SYSTEM_STATE_DATA::ID => {
32813 CONTROL_SYSTEM_STATE_DATA::deser(version, payload).map(Self::CONTROL_SYSTEM_STATE)
32814 }
32815 PARAM_EXT_REQUEST_LIST_DATA::ID => PARAM_EXT_REQUEST_LIST_DATA::deser(version, payload)
32816 .map(Self::PARAM_EXT_REQUEST_LIST),
32817 VIDEO_STREAM_INFORMATION_DATA::ID => {
32818 VIDEO_STREAM_INFORMATION_DATA::deser(version, payload)
32819 .map(Self::VIDEO_STREAM_INFORMATION)
32820 }
32821 RESOURCE_REQUEST_DATA::ID => {
32822 RESOURCE_REQUEST_DATA::deser(version, payload).map(Self::RESOURCE_REQUEST)
32823 }
32824 HIGHRES_IMU_DATA::ID => {
32825 HIGHRES_IMU_DATA::deser(version, payload).map(Self::HIGHRES_IMU)
32826 }
32827 HYGROMETER_SENSOR_DATA::ID => {
32828 HYGROMETER_SENSOR_DATA::deser(version, payload).map(Self::HYGROMETER_SENSOR)
32829 }
32830 MISSION_CURRENT_DATA::ID => {
32831 MISSION_CURRENT_DATA::deser(version, payload).map(Self::MISSION_CURRENT)
32832 }
32833 AVAILABLE_MODES_MONITOR_DATA::ID => {
32834 AVAILABLE_MODES_MONITOR_DATA::deser(version, payload)
32835 .map(Self::AVAILABLE_MODES_MONITOR)
32836 }
32837 POWER_STATUS_DATA::ID => {
32838 POWER_STATUS_DATA::deser(version, payload).map(Self::POWER_STATUS)
32839 }
32840 RAW_RPM_DATA::ID => RAW_RPM_DATA::deser(version, payload).map(Self::RAW_RPM),
32841 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
32842 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::deser(version, payload)
32843 .map(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL)
32844 }
32845 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID => {
32846 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::deser(version, payload)
32847 .map(Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID)
32848 }
32849 LOCAL_POSITION_NED_DATA::ID => {
32850 LOCAL_POSITION_NED_DATA::deser(version, payload).map(Self::LOCAL_POSITION_NED)
32851 }
32852 RAW_IMU_DATA::ID => RAW_IMU_DATA::deser(version, payload).map(Self::RAW_IMU),
32853 PARAM_SET_DATA::ID => PARAM_SET_DATA::deser(version, payload).map(Self::PARAM_SET),
32854 MISSION_REQUEST_DATA::ID => {
32855 MISSION_REQUEST_DATA::deser(version, payload).map(Self::MISSION_REQUEST)
32856 }
32857 SAFETY_ALLOWED_AREA_DATA::ID => {
32858 SAFETY_ALLOWED_AREA_DATA::deser(version, payload).map(Self::SAFETY_ALLOWED_AREA)
32859 }
32860 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => {
32861 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::deser(version, payload)
32862 .map(Self::GIMBAL_DEVICE_ATTITUDE_STATUS)
32863 }
32864 GLOBAL_POSITION_INT_DATA::ID => {
32865 GLOBAL_POSITION_INT_DATA::deser(version, payload).map(Self::GLOBAL_POSITION_INT)
32866 }
32867 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
32868 GLOBAL_VISION_POSITION_ESTIMATE_DATA::deser(version, payload)
32869 .map(Self::GLOBAL_VISION_POSITION_ESTIMATE)
32870 }
32871 TUNNEL_DATA::ID => TUNNEL_DATA::deser(version, payload).map(Self::TUNNEL),
32872 PARAM_EXT_VALUE_DATA::ID => {
32873 PARAM_EXT_VALUE_DATA::deser(version, payload).map(Self::PARAM_EXT_VALUE)
32874 }
32875 TERRAIN_CHECK_DATA::ID => {
32876 TERRAIN_CHECK_DATA::deser(version, payload).map(Self::TERRAIN_CHECK)
32877 }
32878 COMMAND_ACK_DATA::ID => {
32879 COMMAND_ACK_DATA::deser(version, payload).map(Self::COMMAND_ACK)
32880 }
32881 MISSION_ITEM_DATA::ID => {
32882 MISSION_ITEM_DATA::deser(version, payload).map(Self::MISSION_ITEM)
32883 }
32884 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
32885 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::deser(version, payload)
32886 .map(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS)
32887 }
32888 DEBUG_DATA::ID => DEBUG_DATA::deser(version, payload).map(Self::DEBUG),
32889 GPS2_RAW_DATA::ID => GPS2_RAW_DATA::deser(version, payload).map(Self::GPS2_RAW),
32890 ONBOARD_COMPUTER_STATUS_DATA::ID => {
32891 ONBOARD_COMPUTER_STATUS_DATA::deser(version, payload)
32892 .map(Self::ONBOARD_COMPUTER_STATUS)
32893 }
32894 ATTITUDE_TARGET_DATA::ID => {
32895 ATTITUDE_TARGET_DATA::deser(version, payload).map(Self::ATTITUDE_TARGET)
32896 }
32897 RC_CHANNELS_RAW_DATA::ID => {
32898 RC_CHANNELS_RAW_DATA::deser(version, payload).map(Self::RC_CHANNELS_RAW)
32899 }
32900 ODOMETRY_DATA::ID => ODOMETRY_DATA::deser(version, payload).map(Self::ODOMETRY),
32901 VISION_SPEED_ESTIMATE_DATA::ID => {
32902 VISION_SPEED_ESTIMATE_DATA::deser(version, payload).map(Self::VISION_SPEED_ESTIMATE)
32903 }
32904 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
32905 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::deser(version, payload)
32906 .map(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE)
32907 }
32908 ALTITUDE_DATA::ID => ALTITUDE_DATA::deser(version, payload).map(Self::ALTITUDE),
32909 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => {
32910 OPEN_DRONE_ID_AUTHENTICATION_DATA::deser(version, payload)
32911 .map(Self::OPEN_DRONE_ID_AUTHENTICATION)
32912 }
32913 PARAM_REQUEST_LIST_DATA::ID => {
32914 PARAM_REQUEST_LIST_DATA::deser(version, payload).map(Self::PARAM_REQUEST_LIST)
32915 }
32916 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
32917 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::deser(version, payload)
32918 .map(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET)
32919 }
32920 _ => Err(::mavlink_core::error::ParserError::UnknownMessage { id }),
32921 }
32922 }
32923 fn message_name(&self) -> &'static str {
32924 match self {
32925 Self::ACTUATOR_CONTROL_TARGET(..) => ACTUATOR_CONTROL_TARGET_DATA::NAME,
32926 Self::LOG_ERASE(..) => LOG_ERASE_DATA::NAME,
32927 Self::CAMERA_TRACKING_IMAGE_STATUS(..) => CAMERA_TRACKING_IMAGE_STATUS_DATA::NAME,
32928 Self::MISSION_WRITE_PARTIAL_LIST(..) => MISSION_WRITE_PARTIAL_LIST_DATA::NAME,
32929 Self::SCALED_PRESSURE(..) => SCALED_PRESSURE_DATA::NAME,
32930 Self::TRAJECTORY_REPRESENTATION_BEZIER(..) => {
32931 TRAJECTORY_REPRESENTATION_BEZIER_DATA::NAME
32932 }
32933 Self::ORBIT_EXECUTION_STATUS(..) => ORBIT_EXECUTION_STATUS_DATA::NAME,
32934 Self::AUTH_KEY(..) => AUTH_KEY_DATA::NAME,
32935 Self::FILE_TRANSFER_PROTOCOL(..) => FILE_TRANSFER_PROTOCOL_DATA::NAME,
32936 Self::SYS_STATUS(..) => SYS_STATUS_DATA::NAME,
32937 Self::LOG_REQUEST_END(..) => LOG_REQUEST_END_DATA::NAME,
32938 Self::TERRAIN_DATA(..) => TERRAIN_DATA_DATA::NAME,
32939 Self::LOGGING_DATA_ACKED(..) => LOGGING_DATA_ACKED_DATA::NAME,
32940 Self::NAMED_VALUE_FLOAT(..) => NAMED_VALUE_FLOAT_DATA::NAME,
32941 Self::LANDING_TARGET(..) => LANDING_TARGET_DATA::NAME,
32942 Self::ATT_POS_MOCAP(..) => ATT_POS_MOCAP_DATA::NAME,
32943 Self::SCALED_IMU3(..) => SCALED_IMU3_DATA::NAME,
32944 Self::MEMORY_VECT(..) => MEMORY_VECT_DATA::NAME,
32945 Self::TERRAIN_REQUEST(..) => TERRAIN_REQUEST_DATA::NAME,
32946 Self::V2_EXTENSION(..) => V2_EXTENSION_DATA::NAME,
32947 Self::DEBUG_VECT(..) => DEBUG_VECT_DATA::NAME,
32948 Self::MANUAL_CONTROL(..) => MANUAL_CONTROL_DATA::NAME,
32949 Self::AIS_VESSEL(..) => AIS_VESSEL_DATA::NAME,
32950 Self::UAVCAN_NODE_INFO(..) => UAVCAN_NODE_INFO_DATA::NAME,
32951 Self::SET_GPS_GLOBAL_ORIGIN(..) => SET_GPS_GLOBAL_ORIGIN_DATA::NAME,
32952 Self::SCALED_PRESSURE2(..) => SCALED_PRESSURE2_DATA::NAME,
32953 Self::CAMERA_CAPTURE_STATUS(..) => CAMERA_CAPTURE_STATUS_DATA::NAME,
32954 Self::WIFI_CONFIG_AP(..) => WIFI_CONFIG_AP_DATA::NAME,
32955 Self::MISSION_REQUEST_LIST(..) => MISSION_REQUEST_LIST_DATA::NAME,
32956 Self::MISSION_ACK(..) => MISSION_ACK_DATA::NAME,
32957 Self::ENCAPSULATED_DATA(..) => ENCAPSULATED_DATA_DATA::NAME,
32958 Self::UAVIONIX_ADSB_OUT_CFG(..) => UAVIONIX_ADSB_OUT_CFG_DATA::NAME,
32959 Self::EFI_STATUS(..) => EFI_STATUS_DATA::NAME,
32960 Self::OPEN_DRONE_ID_LOCATION(..) => OPEN_DRONE_ID_LOCATION_DATA::NAME,
32961 Self::CAMERA_THERMAL_RANGE(..) => CAMERA_THERMAL_RANGE_DATA::NAME,
32962 Self::LOGGING_ACK(..) => LOGGING_ACK_DATA::NAME,
32963 Self::HIL_CONTROLS(..) => HIL_CONTROLS_DATA::NAME,
32964 Self::GENERATOR_STATUS(..) => GENERATOR_STATUS_DATA::NAME,
32965 Self::FOLLOW_TARGET(..) => FOLLOW_TARGET_DATA::NAME,
32966 Self::VICON_POSITION_ESTIMATE(..) => VICON_POSITION_ESTIMATE_DATA::NAME,
32967 Self::ADSB_VEHICLE(..) => ADSB_VEHICLE_DATA::NAME,
32968 Self::GIMBAL_DEVICE_INFORMATION(..) => GIMBAL_DEVICE_INFORMATION_DATA::NAME,
32969 Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(..) => {
32970 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::NAME
32971 }
32972 Self::SMART_BATTERY_INFO(..) => SMART_BATTERY_INFO_DATA::NAME,
32973 Self::ESC_STATUS(..) => ESC_STATUS_DATA::NAME,
32974 Self::COLLISION(..) => COLLISION_DATA::NAME,
32975 Self::LOGGING_DATA(..) => LOGGING_DATA_DATA::NAME,
32976 Self::GPS_INPUT(..) => GPS_INPUT_DATA::NAME,
32977 Self::HOME_POSITION(..) => HOME_POSITION_DATA::NAME,
32978 Self::PARAM_EXT_REQUEST_READ(..) => PARAM_EXT_REQUEST_READ_DATA::NAME,
32979 Self::LOG_REQUEST_LIST(..) => LOG_REQUEST_LIST_DATA::NAME,
32980 Self::ACTUATOR_OUTPUT_STATUS(..) => ACTUATOR_OUTPUT_STATUS_DATA::NAME,
32981 Self::OBSTACLE_DISTANCE(..) => OBSTACLE_DISTANCE_DATA::NAME,
32982 Self::WIND_COV(..) => WIND_COV_DATA::NAME,
32983 Self::UAVIONIX_ADSB_OUT_DYNAMIC(..) => UAVIONIX_ADSB_OUT_DYNAMIC_DATA::NAME,
32984 Self::UAVIONIX_ADSB_OUT_STATUS(..) => UAVIONIX_ADSB_OUT_STATUS_DATA::NAME,
32985 Self::HIGH_LATENCY2(..) => HIGH_LATENCY2_DATA::NAME,
32986 Self::GIMBAL_DEVICE_SET_ATTITUDE(..) => GIMBAL_DEVICE_SET_ATTITUDE_DATA::NAME,
32987 Self::PARAM_EXT_ACK(..) => PARAM_EXT_ACK_DATA::NAME,
32988 Self::SAFETY_SET_ALLOWED_AREA(..) => SAFETY_SET_ALLOWED_AREA_DATA::NAME,
32989 Self::FENCE_STATUS(..) => FENCE_STATUS_DATA::NAME,
32990 Self::WINCH_STATUS(..) => WINCH_STATUS_DATA::NAME,
32991 Self::ESC_INFO(..) => ESC_INFO_DATA::NAME,
32992 Self::MISSION_REQUEST_PARTIAL_LIST(..) => MISSION_REQUEST_PARTIAL_LIST_DATA::NAME,
32993 Self::NAV_CONTROLLER_OUTPUT(..) => NAV_CONTROLLER_OUTPUT_DATA::NAME,
32994 Self::HIL_OPTICAL_FLOW(..) => HIL_OPTICAL_FLOW_DATA::NAME,
32995 Self::LOG_DATA(..) => LOG_DATA_DATA::NAME,
32996 Self::HIL_STATE_QUATERNION(..) => HIL_STATE_QUATERNION_DATA::NAME,
32997 Self::CURRENT_MODE(..) => CURRENT_MODE_DATA::NAME,
32998 Self::WHEEL_DISTANCE(..) => WHEEL_DISTANCE_DATA::NAME,
32999 Self::OPTICAL_FLOW(..) => OPTICAL_FLOW_DATA::NAME,
33000 Self::CHANGE_OPERATOR_CONTROL(..) => CHANGE_OPERATOR_CONTROL_DATA::NAME,
33001 Self::VIBRATION(..) => VIBRATION_DATA::NAME,
33002 Self::CAMERA_FOV_STATUS(..) => CAMERA_FOV_STATUS_DATA::NAME,
33003 Self::MISSION_COUNT(..) => MISSION_COUNT_DATA::NAME,
33004 Self::OPEN_DRONE_ID_SYSTEM(..) => OPEN_DRONE_ID_SYSTEM_DATA::NAME,
33005 Self::ATTITUDE_QUATERNION_COV(..) => ATTITUDE_QUATERNION_COV_DATA::NAME,
33006 Self::POSITION_TARGET_GLOBAL_INT(..) => POSITION_TARGET_GLOBAL_INT_DATA::NAME,
33007 Self::SET_ACTUATOR_CONTROL_TARGET(..) => SET_ACTUATOR_CONTROL_TARGET_DATA::NAME,
33008 Self::CELLULAR_STATUS(..) => CELLULAR_STATUS_DATA::NAME,
33009 Self::COMPONENT_INFORMATION(..) => COMPONENT_INFORMATION_DATA::NAME,
33010 Self::RADIO_STATUS(..) => RADIO_STATUS_DATA::NAME,
33011 Self::TIMESYNC(..) => TIMESYNC_DATA::NAME,
33012 Self::GIMBAL_MANAGER_STATUS(..) => GIMBAL_MANAGER_STATUS_DATA::NAME,
33013 Self::COMMAND_CANCEL(..) => COMMAND_CANCEL_DATA::NAME,
33014 Self::HIL_ACTUATOR_CONTROLS(..) => HIL_ACTUATOR_CONTROLS_DATA::NAME,
33015 Self::NAMED_VALUE_INT(..) => NAMED_VALUE_INT_DATA::NAME,
33016 Self::DEBUG_FLOAT_ARRAY(..) => DEBUG_FLOAT_ARRAY_DATA::NAME,
33017 Self::OPEN_DRONE_ID_BASIC_ID(..) => OPEN_DRONE_ID_BASIC_ID_DATA::NAME,
33018 Self::COMPONENT_METADATA(..) => COMPONENT_METADATA_DATA::NAME,
33019 Self::LINK_NODE_STATUS(..) => LINK_NODE_STATUS_DATA::NAME,
33020 Self::LOCAL_POSITION_NED_COV(..) => LOCAL_POSITION_NED_COV_DATA::NAME,
33021 Self::CANFD_FRAME(..) => CANFD_FRAME_DATA::NAME,
33022 Self::OPTICAL_FLOW_RAD(..) => OPTICAL_FLOW_RAD_DATA::NAME,
33023 Self::PLAY_TUNE(..) => PLAY_TUNE_DATA::NAME,
33024 Self::COMPONENT_INFORMATION_BASIC(..) => COMPONENT_INFORMATION_BASIC_DATA::NAME,
33025 Self::OPEN_DRONE_ID_SELF_ID(..) => OPEN_DRONE_ID_SELF_ID_DATA::NAME,
33026 Self::HEARTBEAT(..) => HEARTBEAT_DATA::NAME,
33027 Self::EVENT(..) => EVENT_DATA::NAME,
33028 Self::OPEN_DRONE_ID_OPERATOR_ID(..) => OPEN_DRONE_ID_OPERATOR_ID_DATA::NAME,
33029 Self::AVAILABLE_MODES(..) => AVAILABLE_MODES_DATA::NAME,
33030 Self::SET_HOME_POSITION(..) => SET_HOME_POSITION_DATA::NAME,
33031 Self::FUEL_STATUS(..) => FUEL_STATUS_DATA::NAME,
33032 Self::OPEN_DRONE_ID_MESSAGE_PACK(..) => OPEN_DRONE_ID_MESSAGE_PACK_DATA::NAME,
33033 Self::COMMAND_LONG(..) => COMMAND_LONG_DATA::NAME,
33034 Self::GPS_RTK(..) => GPS_RTK_DATA::NAME,
33035 Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(..) => {
33036 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::NAME
33037 }
33038 Self::CAN_FILTER_MODIFY(..) => CAN_FILTER_MODIFY_DATA::NAME,
33039 Self::EXTENDED_SYS_STATE(..) => EXTENDED_SYS_STATE_DATA::NAME,
33040 Self::UAVIONIX_ADSB_GET(..) => UAVIONIX_ADSB_GET_DATA::NAME,
33041 Self::SUPPORTED_TUNES(..) => SUPPORTED_TUNES_DATA::NAME,
33042 Self::DATA_TRANSMISSION_HANDSHAKE(..) => DATA_TRANSMISSION_HANDSHAKE_DATA::NAME,
33043 Self::PARAM_EXT_SET(..) => PARAM_EXT_SET_DATA::NAME,
33044 Self::CAMERA_IMAGE_CAPTURED(..) => CAMERA_IMAGE_CAPTURED_DATA::NAME,
33045 Self::REQUEST_EVENT(..) => REQUEST_EVENT_DATA::NAME,
33046 Self::GLOBAL_POSITION_INT_COV(..) => GLOBAL_POSITION_INT_COV_DATA::NAME,
33047 Self::PARAM_VALUE(..) => PARAM_VALUE_DATA::NAME,
33048 Self::MAG_CAL_REPORT(..) => MAG_CAL_REPORT_DATA::NAME,
33049 Self::MESSAGE_INTERVAL(..) => MESSAGE_INTERVAL_DATA::NAME,
33050 Self::PARAM_MAP_RC(..) => PARAM_MAP_RC_DATA::NAME,
33051 Self::STATUSTEXT(..) => STATUSTEXT_DATA::NAME,
33052 Self::CAMERA_TRACKING_GEO_STATUS(..) => CAMERA_TRACKING_GEO_STATUS_DATA::NAME,
33053 Self::GPS_INJECT_DATA(..) => GPS_INJECT_DATA_DATA::NAME,
33054 Self::VFR_HUD(..) => VFR_HUD_DATA::NAME,
33055 Self::MISSION_ITEM_INT(..) => MISSION_ITEM_INT_DATA::NAME,
33056 Self::ISBD_LINK_STATUS(..) => ISBD_LINK_STATUS_DATA::NAME,
33057 Self::PLAY_TUNE_V2(..) => PLAY_TUNE_V2_DATA::NAME,
33058 Self::CAMERA_SETTINGS(..) => CAMERA_SETTINGS_DATA::NAME,
33059 Self::MISSION_CLEAR_ALL(..) => MISSION_CLEAR_ALL_DATA::NAME,
33060 Self::MANUAL_SETPOINT(..) => MANUAL_SETPOINT_DATA::NAME,
33061 Self::MISSION_SET_CURRENT(..) => MISSION_SET_CURRENT_DATA::NAME,
33062 Self::HIL_GPS(..) => HIL_GPS_DATA::NAME,
33063 Self::REQUEST_DATA_STREAM(..) => REQUEST_DATA_STREAM_DATA::NAME,
33064 Self::HIGH_LATENCY(..) => HIGH_LATENCY_DATA::NAME,
33065 Self::FLIGHT_INFORMATION(..) => FLIGHT_INFORMATION_DATA::NAME,
33066 Self::SERIAL_CONTROL(..) => SERIAL_CONTROL_DATA::NAME,
33067 Self::COMMAND_INT(..) => COMMAND_INT_DATA::NAME,
33068 Self::CAMERA_INFORMATION(..) => CAMERA_INFORMATION_DATA::NAME,
33069 Self::SIM_STATE(..) => SIM_STATE_DATA::NAME,
33070 Self::GPS2_RTK(..) => GPS2_RTK_DATA::NAME,
33071 Self::SERVO_OUTPUT_RAW(..) => SERVO_OUTPUT_RAW_DATA::NAME,
33072 Self::AUTOPILOT_VERSION(..) => AUTOPILOT_VERSION_DATA::NAME,
33073 Self::UAVCAN_NODE_STATUS(..) => UAVCAN_NODE_STATUS_DATA::NAME,
33074 Self::RAW_PRESSURE(..) => RAW_PRESSURE_DATA::NAME,
33075 Self::VIDEO_STREAM_STATUS(..) => VIDEO_STREAM_STATUS_DATA::NAME,
33076 Self::BUTTON_CHANGE(..) => BUTTON_CHANGE_DATA::NAME,
33077 Self::PROTOCOL_VERSION(..) => PROTOCOL_VERSION_DATA::NAME,
33078 Self::DISTANCE_SENSOR(..) => DISTANCE_SENSOR_DATA::NAME,
33079 Self::GIMBAL_MANAGER_SET_ATTITUDE(..) => GIMBAL_MANAGER_SET_ATTITUDE_DATA::NAME,
33080 Self::RC_CHANNELS(..) => RC_CHANNELS_DATA::NAME,
33081 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(..) => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::NAME,
33082 Self::ATTITUDE_QUATERNION(..) => ATTITUDE_QUATERNION_DATA::NAME,
33083 Self::PARAM_REQUEST_READ(..) => PARAM_REQUEST_READ_DATA::NAME,
33084 Self::SCALED_PRESSURE3(..) => SCALED_PRESSURE3_DATA::NAME,
33085 Self::GIMBAL_MANAGER_INFORMATION(..) => GIMBAL_MANAGER_INFORMATION_DATA::NAME,
33086 Self::SETUP_SIGNING(..) => SETUP_SIGNING_DATA::NAME,
33087 Self::LOG_REQUEST_DATA(..) => LOG_REQUEST_DATA_DATA::NAME,
33088 Self::UAVIONIX_ADSB_OUT_CONTROL(..) => UAVIONIX_ADSB_OUT_CONTROL_DATA::NAME,
33089 Self::MISSION_ITEM_REACHED(..) => MISSION_ITEM_REACHED_DATA::NAME,
33090 Self::SET_POSITION_TARGET_GLOBAL_INT(..) => SET_POSITION_TARGET_GLOBAL_INT_DATA::NAME,
33091 Self::RESPONSE_EVENT_ERROR(..) => RESPONSE_EVENT_ERROR_DATA::NAME,
33092 Self::CURRENT_EVENT_SEQUENCE(..) => CURRENT_EVENT_SEQUENCE_DATA::NAME,
33093 Self::CAN_FRAME(..) => CAN_FRAME_DATA::NAME,
33094 Self::MOUNT_ORIENTATION(..) => MOUNT_ORIENTATION_DATA::NAME,
33095 Self::ILLUMINATOR_STATUS(..) => ILLUMINATOR_STATUS_DATA::NAME,
33096 Self::CHANGE_OPERATOR_CONTROL_ACK(..) => CHANGE_OPERATOR_CONTROL_ACK_DATA::NAME,
33097 Self::GIMBAL_MANAGER_SET_PITCHYAW(..) => GIMBAL_MANAGER_SET_PITCHYAW_DATA::NAME,
33098 Self::OPEN_DRONE_ID_ARM_STATUS(..) => OPEN_DRONE_ID_ARM_STATUS_DATA::NAME,
33099 Self::UTM_GLOBAL_POSITION(..) => UTM_GLOBAL_POSITION_DATA::NAME,
33100 Self::RC_CHANNELS_OVERRIDE(..) => RC_CHANNELS_OVERRIDE_DATA::NAME,
33101 Self::SCALED_IMU(..) => SCALED_IMU_DATA::NAME,
33102 Self::DATA_STREAM(..) => DATA_STREAM_DATA::NAME,
33103 Self::LOG_ENTRY(..) => LOG_ENTRY_DATA::NAME,
33104 Self::PING(..) => PING_DATA::NAME,
33105 Self::POSITION_TARGET_LOCAL_NED(..) => POSITION_TARGET_LOCAL_NED_DATA::NAME,
33106 Self::SCALED_IMU2(..) => SCALED_IMU2_DATA::NAME,
33107 Self::GPS_RTCM_DATA(..) => GPS_RTCM_DATA_DATA::NAME,
33108 Self::SET_MODE(..) => SET_MODE_DATA::NAME,
33109 Self::ESTIMATOR_STATUS(..) => ESTIMATOR_STATUS_DATA::NAME,
33110 Self::HIL_STATE(..) => HIL_STATE_DATA::NAME,
33111 Self::SYSTEM_TIME(..) => SYSTEM_TIME_DATA::NAME,
33112 Self::STORAGE_INFORMATION(..) => STORAGE_INFORMATION_DATA::NAME,
33113 Self::BATTERY_INFO(..) => BATTERY_INFO_DATA::NAME,
33114 Self::SET_ATTITUDE_TARGET(..) => SET_ATTITUDE_TARGET_DATA::NAME,
33115 Self::HIL_RC_INPUTS_RAW(..) => HIL_RC_INPUTS_RAW_DATA::NAME,
33116 Self::CAMERA_TRIGGER(..) => CAMERA_TRIGGER_DATA::NAME,
33117 Self::TIME_ESTIMATE_TO_TARGET(..) => TIME_ESTIMATE_TO_TARGET_DATA::NAME,
33118 Self::HIL_SENSOR(..) => HIL_SENSOR_DATA::NAME,
33119 Self::MISSION_REQUEST_INT(..) => MISSION_REQUEST_INT_DATA::NAME,
33120 Self::TERRAIN_REPORT(..) => TERRAIN_REPORT_DATA::NAME,
33121 Self::BATTERY_STATUS(..) => BATTERY_STATUS_DATA::NAME,
33122 Self::GPS_RAW_INT(..) => GPS_RAW_INT_DATA::NAME,
33123 Self::VISION_POSITION_ESTIMATE(..) => VISION_POSITION_ESTIMATE_DATA::NAME,
33124 Self::CELLULAR_CONFIG(..) => CELLULAR_CONFIG_DATA::NAME,
33125 Self::SET_POSITION_TARGET_LOCAL_NED(..) => SET_POSITION_TARGET_LOCAL_NED_DATA::NAME,
33126 Self::GPS_GLOBAL_ORIGIN(..) => GPS_GLOBAL_ORIGIN_DATA::NAME,
33127 Self::RC_CHANNELS_SCALED(..) => RC_CHANNELS_SCALED_DATA::NAME,
33128 Self::ATTITUDE(..) => ATTITUDE_DATA::NAME,
33129 Self::GPS_STATUS(..) => GPS_STATUS_DATA::NAME,
33130 Self::CONTROL_SYSTEM_STATE(..) => CONTROL_SYSTEM_STATE_DATA::NAME,
33131 Self::PARAM_EXT_REQUEST_LIST(..) => PARAM_EXT_REQUEST_LIST_DATA::NAME,
33132 Self::VIDEO_STREAM_INFORMATION(..) => VIDEO_STREAM_INFORMATION_DATA::NAME,
33133 Self::RESOURCE_REQUEST(..) => RESOURCE_REQUEST_DATA::NAME,
33134 Self::HIGHRES_IMU(..) => HIGHRES_IMU_DATA::NAME,
33135 Self::HYGROMETER_SENSOR(..) => HYGROMETER_SENSOR_DATA::NAME,
33136 Self::MISSION_CURRENT(..) => MISSION_CURRENT_DATA::NAME,
33137 Self::AVAILABLE_MODES_MONITOR(..) => AVAILABLE_MODES_MONITOR_DATA::NAME,
33138 Self::POWER_STATUS(..) => POWER_STATUS_DATA::NAME,
33139 Self::RAW_RPM(..) => RAW_RPM_DATA::NAME,
33140 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(..) => {
33141 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::NAME
33142 }
33143 Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(..) => UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::NAME,
33144 Self::LOCAL_POSITION_NED(..) => LOCAL_POSITION_NED_DATA::NAME,
33145 Self::RAW_IMU(..) => RAW_IMU_DATA::NAME,
33146 Self::PARAM_SET(..) => PARAM_SET_DATA::NAME,
33147 Self::MISSION_REQUEST(..) => MISSION_REQUEST_DATA::NAME,
33148 Self::SAFETY_ALLOWED_AREA(..) => SAFETY_ALLOWED_AREA_DATA::NAME,
33149 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(..) => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::NAME,
33150 Self::GLOBAL_POSITION_INT(..) => GLOBAL_POSITION_INT_DATA::NAME,
33151 Self::GLOBAL_VISION_POSITION_ESTIMATE(..) => GLOBAL_VISION_POSITION_ESTIMATE_DATA::NAME,
33152 Self::TUNNEL(..) => TUNNEL_DATA::NAME,
33153 Self::PARAM_EXT_VALUE(..) => PARAM_EXT_VALUE_DATA::NAME,
33154 Self::TERRAIN_CHECK(..) => TERRAIN_CHECK_DATA::NAME,
33155 Self::COMMAND_ACK(..) => COMMAND_ACK_DATA::NAME,
33156 Self::MISSION_ITEM(..) => MISSION_ITEM_DATA::NAME,
33157 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(..) => {
33158 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::NAME
33159 }
33160 Self::DEBUG(..) => DEBUG_DATA::NAME,
33161 Self::GPS2_RAW(..) => GPS2_RAW_DATA::NAME,
33162 Self::ONBOARD_COMPUTER_STATUS(..) => ONBOARD_COMPUTER_STATUS_DATA::NAME,
33163 Self::ATTITUDE_TARGET(..) => ATTITUDE_TARGET_DATA::NAME,
33164 Self::RC_CHANNELS_RAW(..) => RC_CHANNELS_RAW_DATA::NAME,
33165 Self::ODOMETRY(..) => ODOMETRY_DATA::NAME,
33166 Self::VISION_SPEED_ESTIMATE(..) => VISION_SPEED_ESTIMATE_DATA::NAME,
33167 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(..) => {
33168 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::NAME
33169 }
33170 Self::ALTITUDE(..) => ALTITUDE_DATA::NAME,
33171 Self::OPEN_DRONE_ID_AUTHENTICATION(..) => OPEN_DRONE_ID_AUTHENTICATION_DATA::NAME,
33172 Self::PARAM_REQUEST_LIST(..) => PARAM_REQUEST_LIST_DATA::NAME,
33173 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(..) => {
33174 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::NAME
33175 }
33176 }
33177 }
33178 fn message_id(&self) -> u32 {
33179 match self {
33180 Self::ACTUATOR_CONTROL_TARGET(..) => ACTUATOR_CONTROL_TARGET_DATA::ID,
33181 Self::LOG_ERASE(..) => LOG_ERASE_DATA::ID,
33182 Self::CAMERA_TRACKING_IMAGE_STATUS(..) => CAMERA_TRACKING_IMAGE_STATUS_DATA::ID,
33183 Self::MISSION_WRITE_PARTIAL_LIST(..) => MISSION_WRITE_PARTIAL_LIST_DATA::ID,
33184 Self::SCALED_PRESSURE(..) => SCALED_PRESSURE_DATA::ID,
33185 Self::TRAJECTORY_REPRESENTATION_BEZIER(..) => TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID,
33186 Self::ORBIT_EXECUTION_STATUS(..) => ORBIT_EXECUTION_STATUS_DATA::ID,
33187 Self::AUTH_KEY(..) => AUTH_KEY_DATA::ID,
33188 Self::FILE_TRANSFER_PROTOCOL(..) => FILE_TRANSFER_PROTOCOL_DATA::ID,
33189 Self::SYS_STATUS(..) => SYS_STATUS_DATA::ID,
33190 Self::LOG_REQUEST_END(..) => LOG_REQUEST_END_DATA::ID,
33191 Self::TERRAIN_DATA(..) => TERRAIN_DATA_DATA::ID,
33192 Self::LOGGING_DATA_ACKED(..) => LOGGING_DATA_ACKED_DATA::ID,
33193 Self::NAMED_VALUE_FLOAT(..) => NAMED_VALUE_FLOAT_DATA::ID,
33194 Self::LANDING_TARGET(..) => LANDING_TARGET_DATA::ID,
33195 Self::ATT_POS_MOCAP(..) => ATT_POS_MOCAP_DATA::ID,
33196 Self::SCALED_IMU3(..) => SCALED_IMU3_DATA::ID,
33197 Self::MEMORY_VECT(..) => MEMORY_VECT_DATA::ID,
33198 Self::TERRAIN_REQUEST(..) => TERRAIN_REQUEST_DATA::ID,
33199 Self::V2_EXTENSION(..) => V2_EXTENSION_DATA::ID,
33200 Self::DEBUG_VECT(..) => DEBUG_VECT_DATA::ID,
33201 Self::MANUAL_CONTROL(..) => MANUAL_CONTROL_DATA::ID,
33202 Self::AIS_VESSEL(..) => AIS_VESSEL_DATA::ID,
33203 Self::UAVCAN_NODE_INFO(..) => UAVCAN_NODE_INFO_DATA::ID,
33204 Self::SET_GPS_GLOBAL_ORIGIN(..) => SET_GPS_GLOBAL_ORIGIN_DATA::ID,
33205 Self::SCALED_PRESSURE2(..) => SCALED_PRESSURE2_DATA::ID,
33206 Self::CAMERA_CAPTURE_STATUS(..) => CAMERA_CAPTURE_STATUS_DATA::ID,
33207 Self::WIFI_CONFIG_AP(..) => WIFI_CONFIG_AP_DATA::ID,
33208 Self::MISSION_REQUEST_LIST(..) => MISSION_REQUEST_LIST_DATA::ID,
33209 Self::MISSION_ACK(..) => MISSION_ACK_DATA::ID,
33210 Self::ENCAPSULATED_DATA(..) => ENCAPSULATED_DATA_DATA::ID,
33211 Self::UAVIONIX_ADSB_OUT_CFG(..) => UAVIONIX_ADSB_OUT_CFG_DATA::ID,
33212 Self::EFI_STATUS(..) => EFI_STATUS_DATA::ID,
33213 Self::OPEN_DRONE_ID_LOCATION(..) => OPEN_DRONE_ID_LOCATION_DATA::ID,
33214 Self::CAMERA_THERMAL_RANGE(..) => CAMERA_THERMAL_RANGE_DATA::ID,
33215 Self::LOGGING_ACK(..) => LOGGING_ACK_DATA::ID,
33216 Self::HIL_CONTROLS(..) => HIL_CONTROLS_DATA::ID,
33217 Self::GENERATOR_STATUS(..) => GENERATOR_STATUS_DATA::ID,
33218 Self::FOLLOW_TARGET(..) => FOLLOW_TARGET_DATA::ID,
33219 Self::VICON_POSITION_ESTIMATE(..) => VICON_POSITION_ESTIMATE_DATA::ID,
33220 Self::ADSB_VEHICLE(..) => ADSB_VEHICLE_DATA::ID,
33221 Self::GIMBAL_DEVICE_INFORMATION(..) => GIMBAL_DEVICE_INFORMATION_DATA::ID,
33222 Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(..) => {
33223 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID
33224 }
33225 Self::SMART_BATTERY_INFO(..) => SMART_BATTERY_INFO_DATA::ID,
33226 Self::ESC_STATUS(..) => ESC_STATUS_DATA::ID,
33227 Self::COLLISION(..) => COLLISION_DATA::ID,
33228 Self::LOGGING_DATA(..) => LOGGING_DATA_DATA::ID,
33229 Self::GPS_INPUT(..) => GPS_INPUT_DATA::ID,
33230 Self::HOME_POSITION(..) => HOME_POSITION_DATA::ID,
33231 Self::PARAM_EXT_REQUEST_READ(..) => PARAM_EXT_REQUEST_READ_DATA::ID,
33232 Self::LOG_REQUEST_LIST(..) => LOG_REQUEST_LIST_DATA::ID,
33233 Self::ACTUATOR_OUTPUT_STATUS(..) => ACTUATOR_OUTPUT_STATUS_DATA::ID,
33234 Self::OBSTACLE_DISTANCE(..) => OBSTACLE_DISTANCE_DATA::ID,
33235 Self::WIND_COV(..) => WIND_COV_DATA::ID,
33236 Self::UAVIONIX_ADSB_OUT_DYNAMIC(..) => UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID,
33237 Self::UAVIONIX_ADSB_OUT_STATUS(..) => UAVIONIX_ADSB_OUT_STATUS_DATA::ID,
33238 Self::HIGH_LATENCY2(..) => HIGH_LATENCY2_DATA::ID,
33239 Self::GIMBAL_DEVICE_SET_ATTITUDE(..) => GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID,
33240 Self::PARAM_EXT_ACK(..) => PARAM_EXT_ACK_DATA::ID,
33241 Self::SAFETY_SET_ALLOWED_AREA(..) => SAFETY_SET_ALLOWED_AREA_DATA::ID,
33242 Self::FENCE_STATUS(..) => FENCE_STATUS_DATA::ID,
33243 Self::WINCH_STATUS(..) => WINCH_STATUS_DATA::ID,
33244 Self::ESC_INFO(..) => ESC_INFO_DATA::ID,
33245 Self::MISSION_REQUEST_PARTIAL_LIST(..) => MISSION_REQUEST_PARTIAL_LIST_DATA::ID,
33246 Self::NAV_CONTROLLER_OUTPUT(..) => NAV_CONTROLLER_OUTPUT_DATA::ID,
33247 Self::HIL_OPTICAL_FLOW(..) => HIL_OPTICAL_FLOW_DATA::ID,
33248 Self::LOG_DATA(..) => LOG_DATA_DATA::ID,
33249 Self::HIL_STATE_QUATERNION(..) => HIL_STATE_QUATERNION_DATA::ID,
33250 Self::CURRENT_MODE(..) => CURRENT_MODE_DATA::ID,
33251 Self::WHEEL_DISTANCE(..) => WHEEL_DISTANCE_DATA::ID,
33252 Self::OPTICAL_FLOW(..) => OPTICAL_FLOW_DATA::ID,
33253 Self::CHANGE_OPERATOR_CONTROL(..) => CHANGE_OPERATOR_CONTROL_DATA::ID,
33254 Self::VIBRATION(..) => VIBRATION_DATA::ID,
33255 Self::CAMERA_FOV_STATUS(..) => CAMERA_FOV_STATUS_DATA::ID,
33256 Self::MISSION_COUNT(..) => MISSION_COUNT_DATA::ID,
33257 Self::OPEN_DRONE_ID_SYSTEM(..) => OPEN_DRONE_ID_SYSTEM_DATA::ID,
33258 Self::ATTITUDE_QUATERNION_COV(..) => ATTITUDE_QUATERNION_COV_DATA::ID,
33259 Self::POSITION_TARGET_GLOBAL_INT(..) => POSITION_TARGET_GLOBAL_INT_DATA::ID,
33260 Self::SET_ACTUATOR_CONTROL_TARGET(..) => SET_ACTUATOR_CONTROL_TARGET_DATA::ID,
33261 Self::CELLULAR_STATUS(..) => CELLULAR_STATUS_DATA::ID,
33262 Self::COMPONENT_INFORMATION(..) => COMPONENT_INFORMATION_DATA::ID,
33263 Self::RADIO_STATUS(..) => RADIO_STATUS_DATA::ID,
33264 Self::TIMESYNC(..) => TIMESYNC_DATA::ID,
33265 Self::GIMBAL_MANAGER_STATUS(..) => GIMBAL_MANAGER_STATUS_DATA::ID,
33266 Self::COMMAND_CANCEL(..) => COMMAND_CANCEL_DATA::ID,
33267 Self::HIL_ACTUATOR_CONTROLS(..) => HIL_ACTUATOR_CONTROLS_DATA::ID,
33268 Self::NAMED_VALUE_INT(..) => NAMED_VALUE_INT_DATA::ID,
33269 Self::DEBUG_FLOAT_ARRAY(..) => DEBUG_FLOAT_ARRAY_DATA::ID,
33270 Self::OPEN_DRONE_ID_BASIC_ID(..) => OPEN_DRONE_ID_BASIC_ID_DATA::ID,
33271 Self::COMPONENT_METADATA(..) => COMPONENT_METADATA_DATA::ID,
33272 Self::LINK_NODE_STATUS(..) => LINK_NODE_STATUS_DATA::ID,
33273 Self::LOCAL_POSITION_NED_COV(..) => LOCAL_POSITION_NED_COV_DATA::ID,
33274 Self::CANFD_FRAME(..) => CANFD_FRAME_DATA::ID,
33275 Self::OPTICAL_FLOW_RAD(..) => OPTICAL_FLOW_RAD_DATA::ID,
33276 Self::PLAY_TUNE(..) => PLAY_TUNE_DATA::ID,
33277 Self::COMPONENT_INFORMATION_BASIC(..) => COMPONENT_INFORMATION_BASIC_DATA::ID,
33278 Self::OPEN_DRONE_ID_SELF_ID(..) => OPEN_DRONE_ID_SELF_ID_DATA::ID,
33279 Self::HEARTBEAT(..) => HEARTBEAT_DATA::ID,
33280 Self::EVENT(..) => EVENT_DATA::ID,
33281 Self::OPEN_DRONE_ID_OPERATOR_ID(..) => OPEN_DRONE_ID_OPERATOR_ID_DATA::ID,
33282 Self::AVAILABLE_MODES(..) => AVAILABLE_MODES_DATA::ID,
33283 Self::SET_HOME_POSITION(..) => SET_HOME_POSITION_DATA::ID,
33284 Self::FUEL_STATUS(..) => FUEL_STATUS_DATA::ID,
33285 Self::OPEN_DRONE_ID_MESSAGE_PACK(..) => OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID,
33286 Self::COMMAND_LONG(..) => COMMAND_LONG_DATA::ID,
33287 Self::GPS_RTK(..) => GPS_RTK_DATA::ID,
33288 Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(..) => {
33289 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID
33290 }
33291 Self::CAN_FILTER_MODIFY(..) => CAN_FILTER_MODIFY_DATA::ID,
33292 Self::EXTENDED_SYS_STATE(..) => EXTENDED_SYS_STATE_DATA::ID,
33293 Self::UAVIONIX_ADSB_GET(..) => UAVIONIX_ADSB_GET_DATA::ID,
33294 Self::SUPPORTED_TUNES(..) => SUPPORTED_TUNES_DATA::ID,
33295 Self::DATA_TRANSMISSION_HANDSHAKE(..) => DATA_TRANSMISSION_HANDSHAKE_DATA::ID,
33296 Self::PARAM_EXT_SET(..) => PARAM_EXT_SET_DATA::ID,
33297 Self::CAMERA_IMAGE_CAPTURED(..) => CAMERA_IMAGE_CAPTURED_DATA::ID,
33298 Self::REQUEST_EVENT(..) => REQUEST_EVENT_DATA::ID,
33299 Self::GLOBAL_POSITION_INT_COV(..) => GLOBAL_POSITION_INT_COV_DATA::ID,
33300 Self::PARAM_VALUE(..) => PARAM_VALUE_DATA::ID,
33301 Self::MAG_CAL_REPORT(..) => MAG_CAL_REPORT_DATA::ID,
33302 Self::MESSAGE_INTERVAL(..) => MESSAGE_INTERVAL_DATA::ID,
33303 Self::PARAM_MAP_RC(..) => PARAM_MAP_RC_DATA::ID,
33304 Self::STATUSTEXT(..) => STATUSTEXT_DATA::ID,
33305 Self::CAMERA_TRACKING_GEO_STATUS(..) => CAMERA_TRACKING_GEO_STATUS_DATA::ID,
33306 Self::GPS_INJECT_DATA(..) => GPS_INJECT_DATA_DATA::ID,
33307 Self::VFR_HUD(..) => VFR_HUD_DATA::ID,
33308 Self::MISSION_ITEM_INT(..) => MISSION_ITEM_INT_DATA::ID,
33309 Self::ISBD_LINK_STATUS(..) => ISBD_LINK_STATUS_DATA::ID,
33310 Self::PLAY_TUNE_V2(..) => PLAY_TUNE_V2_DATA::ID,
33311 Self::CAMERA_SETTINGS(..) => CAMERA_SETTINGS_DATA::ID,
33312 Self::MISSION_CLEAR_ALL(..) => MISSION_CLEAR_ALL_DATA::ID,
33313 Self::MANUAL_SETPOINT(..) => MANUAL_SETPOINT_DATA::ID,
33314 Self::MISSION_SET_CURRENT(..) => MISSION_SET_CURRENT_DATA::ID,
33315 Self::HIL_GPS(..) => HIL_GPS_DATA::ID,
33316 Self::REQUEST_DATA_STREAM(..) => REQUEST_DATA_STREAM_DATA::ID,
33317 Self::HIGH_LATENCY(..) => HIGH_LATENCY_DATA::ID,
33318 Self::FLIGHT_INFORMATION(..) => FLIGHT_INFORMATION_DATA::ID,
33319 Self::SERIAL_CONTROL(..) => SERIAL_CONTROL_DATA::ID,
33320 Self::COMMAND_INT(..) => COMMAND_INT_DATA::ID,
33321 Self::CAMERA_INFORMATION(..) => CAMERA_INFORMATION_DATA::ID,
33322 Self::SIM_STATE(..) => SIM_STATE_DATA::ID,
33323 Self::GPS2_RTK(..) => GPS2_RTK_DATA::ID,
33324 Self::SERVO_OUTPUT_RAW(..) => SERVO_OUTPUT_RAW_DATA::ID,
33325 Self::AUTOPILOT_VERSION(..) => AUTOPILOT_VERSION_DATA::ID,
33326 Self::UAVCAN_NODE_STATUS(..) => UAVCAN_NODE_STATUS_DATA::ID,
33327 Self::RAW_PRESSURE(..) => RAW_PRESSURE_DATA::ID,
33328 Self::VIDEO_STREAM_STATUS(..) => VIDEO_STREAM_STATUS_DATA::ID,
33329 Self::BUTTON_CHANGE(..) => BUTTON_CHANGE_DATA::ID,
33330 Self::PROTOCOL_VERSION(..) => PROTOCOL_VERSION_DATA::ID,
33331 Self::DISTANCE_SENSOR(..) => DISTANCE_SENSOR_DATA::ID,
33332 Self::GIMBAL_MANAGER_SET_ATTITUDE(..) => GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID,
33333 Self::RC_CHANNELS(..) => RC_CHANNELS_DATA::ID,
33334 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(..) => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID,
33335 Self::ATTITUDE_QUATERNION(..) => ATTITUDE_QUATERNION_DATA::ID,
33336 Self::PARAM_REQUEST_READ(..) => PARAM_REQUEST_READ_DATA::ID,
33337 Self::SCALED_PRESSURE3(..) => SCALED_PRESSURE3_DATA::ID,
33338 Self::GIMBAL_MANAGER_INFORMATION(..) => GIMBAL_MANAGER_INFORMATION_DATA::ID,
33339 Self::SETUP_SIGNING(..) => SETUP_SIGNING_DATA::ID,
33340 Self::LOG_REQUEST_DATA(..) => LOG_REQUEST_DATA_DATA::ID,
33341 Self::UAVIONIX_ADSB_OUT_CONTROL(..) => UAVIONIX_ADSB_OUT_CONTROL_DATA::ID,
33342 Self::MISSION_ITEM_REACHED(..) => MISSION_ITEM_REACHED_DATA::ID,
33343 Self::SET_POSITION_TARGET_GLOBAL_INT(..) => SET_POSITION_TARGET_GLOBAL_INT_DATA::ID,
33344 Self::RESPONSE_EVENT_ERROR(..) => RESPONSE_EVENT_ERROR_DATA::ID,
33345 Self::CURRENT_EVENT_SEQUENCE(..) => CURRENT_EVENT_SEQUENCE_DATA::ID,
33346 Self::CAN_FRAME(..) => CAN_FRAME_DATA::ID,
33347 Self::MOUNT_ORIENTATION(..) => MOUNT_ORIENTATION_DATA::ID,
33348 Self::ILLUMINATOR_STATUS(..) => ILLUMINATOR_STATUS_DATA::ID,
33349 Self::CHANGE_OPERATOR_CONTROL_ACK(..) => CHANGE_OPERATOR_CONTROL_ACK_DATA::ID,
33350 Self::GIMBAL_MANAGER_SET_PITCHYAW(..) => GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID,
33351 Self::OPEN_DRONE_ID_ARM_STATUS(..) => OPEN_DRONE_ID_ARM_STATUS_DATA::ID,
33352 Self::UTM_GLOBAL_POSITION(..) => UTM_GLOBAL_POSITION_DATA::ID,
33353 Self::RC_CHANNELS_OVERRIDE(..) => RC_CHANNELS_OVERRIDE_DATA::ID,
33354 Self::SCALED_IMU(..) => SCALED_IMU_DATA::ID,
33355 Self::DATA_STREAM(..) => DATA_STREAM_DATA::ID,
33356 Self::LOG_ENTRY(..) => LOG_ENTRY_DATA::ID,
33357 Self::PING(..) => PING_DATA::ID,
33358 Self::POSITION_TARGET_LOCAL_NED(..) => POSITION_TARGET_LOCAL_NED_DATA::ID,
33359 Self::SCALED_IMU2(..) => SCALED_IMU2_DATA::ID,
33360 Self::GPS_RTCM_DATA(..) => GPS_RTCM_DATA_DATA::ID,
33361 Self::SET_MODE(..) => SET_MODE_DATA::ID,
33362 Self::ESTIMATOR_STATUS(..) => ESTIMATOR_STATUS_DATA::ID,
33363 Self::HIL_STATE(..) => HIL_STATE_DATA::ID,
33364 Self::SYSTEM_TIME(..) => SYSTEM_TIME_DATA::ID,
33365 Self::STORAGE_INFORMATION(..) => STORAGE_INFORMATION_DATA::ID,
33366 Self::BATTERY_INFO(..) => BATTERY_INFO_DATA::ID,
33367 Self::SET_ATTITUDE_TARGET(..) => SET_ATTITUDE_TARGET_DATA::ID,
33368 Self::HIL_RC_INPUTS_RAW(..) => HIL_RC_INPUTS_RAW_DATA::ID,
33369 Self::CAMERA_TRIGGER(..) => CAMERA_TRIGGER_DATA::ID,
33370 Self::TIME_ESTIMATE_TO_TARGET(..) => TIME_ESTIMATE_TO_TARGET_DATA::ID,
33371 Self::HIL_SENSOR(..) => HIL_SENSOR_DATA::ID,
33372 Self::MISSION_REQUEST_INT(..) => MISSION_REQUEST_INT_DATA::ID,
33373 Self::TERRAIN_REPORT(..) => TERRAIN_REPORT_DATA::ID,
33374 Self::BATTERY_STATUS(..) => BATTERY_STATUS_DATA::ID,
33375 Self::GPS_RAW_INT(..) => GPS_RAW_INT_DATA::ID,
33376 Self::VISION_POSITION_ESTIMATE(..) => VISION_POSITION_ESTIMATE_DATA::ID,
33377 Self::CELLULAR_CONFIG(..) => CELLULAR_CONFIG_DATA::ID,
33378 Self::SET_POSITION_TARGET_LOCAL_NED(..) => SET_POSITION_TARGET_LOCAL_NED_DATA::ID,
33379 Self::GPS_GLOBAL_ORIGIN(..) => GPS_GLOBAL_ORIGIN_DATA::ID,
33380 Self::RC_CHANNELS_SCALED(..) => RC_CHANNELS_SCALED_DATA::ID,
33381 Self::ATTITUDE(..) => ATTITUDE_DATA::ID,
33382 Self::GPS_STATUS(..) => GPS_STATUS_DATA::ID,
33383 Self::CONTROL_SYSTEM_STATE(..) => CONTROL_SYSTEM_STATE_DATA::ID,
33384 Self::PARAM_EXT_REQUEST_LIST(..) => PARAM_EXT_REQUEST_LIST_DATA::ID,
33385 Self::VIDEO_STREAM_INFORMATION(..) => VIDEO_STREAM_INFORMATION_DATA::ID,
33386 Self::RESOURCE_REQUEST(..) => RESOURCE_REQUEST_DATA::ID,
33387 Self::HIGHRES_IMU(..) => HIGHRES_IMU_DATA::ID,
33388 Self::HYGROMETER_SENSOR(..) => HYGROMETER_SENSOR_DATA::ID,
33389 Self::MISSION_CURRENT(..) => MISSION_CURRENT_DATA::ID,
33390 Self::AVAILABLE_MODES_MONITOR(..) => AVAILABLE_MODES_MONITOR_DATA::ID,
33391 Self::POWER_STATUS(..) => POWER_STATUS_DATA::ID,
33392 Self::RAW_RPM(..) => RAW_RPM_DATA::ID,
33393 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(..) => {
33394 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID
33395 }
33396 Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(..) => UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID,
33397 Self::LOCAL_POSITION_NED(..) => LOCAL_POSITION_NED_DATA::ID,
33398 Self::RAW_IMU(..) => RAW_IMU_DATA::ID,
33399 Self::PARAM_SET(..) => PARAM_SET_DATA::ID,
33400 Self::MISSION_REQUEST(..) => MISSION_REQUEST_DATA::ID,
33401 Self::SAFETY_ALLOWED_AREA(..) => SAFETY_ALLOWED_AREA_DATA::ID,
33402 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(..) => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID,
33403 Self::GLOBAL_POSITION_INT(..) => GLOBAL_POSITION_INT_DATA::ID,
33404 Self::GLOBAL_VISION_POSITION_ESTIMATE(..) => GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID,
33405 Self::TUNNEL(..) => TUNNEL_DATA::ID,
33406 Self::PARAM_EXT_VALUE(..) => PARAM_EXT_VALUE_DATA::ID,
33407 Self::TERRAIN_CHECK(..) => TERRAIN_CHECK_DATA::ID,
33408 Self::COMMAND_ACK(..) => COMMAND_ACK_DATA::ID,
33409 Self::MISSION_ITEM(..) => MISSION_ITEM_DATA::ID,
33410 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(..) => {
33411 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID
33412 }
33413 Self::DEBUG(..) => DEBUG_DATA::ID,
33414 Self::GPS2_RAW(..) => GPS2_RAW_DATA::ID,
33415 Self::ONBOARD_COMPUTER_STATUS(..) => ONBOARD_COMPUTER_STATUS_DATA::ID,
33416 Self::ATTITUDE_TARGET(..) => ATTITUDE_TARGET_DATA::ID,
33417 Self::RC_CHANNELS_RAW(..) => RC_CHANNELS_RAW_DATA::ID,
33418 Self::ODOMETRY(..) => ODOMETRY_DATA::ID,
33419 Self::VISION_SPEED_ESTIMATE(..) => VISION_SPEED_ESTIMATE_DATA::ID,
33420 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(..) => {
33421 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID
33422 }
33423 Self::ALTITUDE(..) => ALTITUDE_DATA::ID,
33424 Self::OPEN_DRONE_ID_AUTHENTICATION(..) => OPEN_DRONE_ID_AUTHENTICATION_DATA::ID,
33425 Self::PARAM_REQUEST_LIST(..) => PARAM_REQUEST_LIST_DATA::ID,
33426 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(..) => {
33427 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID
33428 }
33429 }
33430 }
33431 fn message_id_from_name(name: &str) -> Option<u32> {
33432 match name {
33433 ACTUATOR_CONTROL_TARGET_DATA::NAME => Some(ACTUATOR_CONTROL_TARGET_DATA::ID),
33434 LOG_ERASE_DATA::NAME => Some(LOG_ERASE_DATA::ID),
33435 CAMERA_TRACKING_IMAGE_STATUS_DATA::NAME => Some(CAMERA_TRACKING_IMAGE_STATUS_DATA::ID),
33436 MISSION_WRITE_PARTIAL_LIST_DATA::NAME => Some(MISSION_WRITE_PARTIAL_LIST_DATA::ID),
33437 SCALED_PRESSURE_DATA::NAME => Some(SCALED_PRESSURE_DATA::ID),
33438 TRAJECTORY_REPRESENTATION_BEZIER_DATA::NAME => {
33439 Some(TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID)
33440 }
33441 ORBIT_EXECUTION_STATUS_DATA::NAME => Some(ORBIT_EXECUTION_STATUS_DATA::ID),
33442 AUTH_KEY_DATA::NAME => Some(AUTH_KEY_DATA::ID),
33443 FILE_TRANSFER_PROTOCOL_DATA::NAME => Some(FILE_TRANSFER_PROTOCOL_DATA::ID),
33444 SYS_STATUS_DATA::NAME => Some(SYS_STATUS_DATA::ID),
33445 LOG_REQUEST_END_DATA::NAME => Some(LOG_REQUEST_END_DATA::ID),
33446 TERRAIN_DATA_DATA::NAME => Some(TERRAIN_DATA_DATA::ID),
33447 LOGGING_DATA_ACKED_DATA::NAME => Some(LOGGING_DATA_ACKED_DATA::ID),
33448 NAMED_VALUE_FLOAT_DATA::NAME => Some(NAMED_VALUE_FLOAT_DATA::ID),
33449 LANDING_TARGET_DATA::NAME => Some(LANDING_TARGET_DATA::ID),
33450 ATT_POS_MOCAP_DATA::NAME => Some(ATT_POS_MOCAP_DATA::ID),
33451 SCALED_IMU3_DATA::NAME => Some(SCALED_IMU3_DATA::ID),
33452 MEMORY_VECT_DATA::NAME => Some(MEMORY_VECT_DATA::ID),
33453 TERRAIN_REQUEST_DATA::NAME => Some(TERRAIN_REQUEST_DATA::ID),
33454 V2_EXTENSION_DATA::NAME => Some(V2_EXTENSION_DATA::ID),
33455 DEBUG_VECT_DATA::NAME => Some(DEBUG_VECT_DATA::ID),
33456 MANUAL_CONTROL_DATA::NAME => Some(MANUAL_CONTROL_DATA::ID),
33457 AIS_VESSEL_DATA::NAME => Some(AIS_VESSEL_DATA::ID),
33458 UAVCAN_NODE_INFO_DATA::NAME => Some(UAVCAN_NODE_INFO_DATA::ID),
33459 SET_GPS_GLOBAL_ORIGIN_DATA::NAME => Some(SET_GPS_GLOBAL_ORIGIN_DATA::ID),
33460 SCALED_PRESSURE2_DATA::NAME => Some(SCALED_PRESSURE2_DATA::ID),
33461 CAMERA_CAPTURE_STATUS_DATA::NAME => Some(CAMERA_CAPTURE_STATUS_DATA::ID),
33462 WIFI_CONFIG_AP_DATA::NAME => Some(WIFI_CONFIG_AP_DATA::ID),
33463 MISSION_REQUEST_LIST_DATA::NAME => Some(MISSION_REQUEST_LIST_DATA::ID),
33464 MISSION_ACK_DATA::NAME => Some(MISSION_ACK_DATA::ID),
33465 ENCAPSULATED_DATA_DATA::NAME => Some(ENCAPSULATED_DATA_DATA::ID),
33466 UAVIONIX_ADSB_OUT_CFG_DATA::NAME => Some(UAVIONIX_ADSB_OUT_CFG_DATA::ID),
33467 EFI_STATUS_DATA::NAME => Some(EFI_STATUS_DATA::ID),
33468 OPEN_DRONE_ID_LOCATION_DATA::NAME => Some(OPEN_DRONE_ID_LOCATION_DATA::ID),
33469 CAMERA_THERMAL_RANGE_DATA::NAME => Some(CAMERA_THERMAL_RANGE_DATA::ID),
33470 LOGGING_ACK_DATA::NAME => Some(LOGGING_ACK_DATA::ID),
33471 HIL_CONTROLS_DATA::NAME => Some(HIL_CONTROLS_DATA::ID),
33472 GENERATOR_STATUS_DATA::NAME => Some(GENERATOR_STATUS_DATA::ID),
33473 FOLLOW_TARGET_DATA::NAME => Some(FOLLOW_TARGET_DATA::ID),
33474 VICON_POSITION_ESTIMATE_DATA::NAME => Some(VICON_POSITION_ESTIMATE_DATA::ID),
33475 ADSB_VEHICLE_DATA::NAME => Some(ADSB_VEHICLE_DATA::ID),
33476 GIMBAL_DEVICE_INFORMATION_DATA::NAME => Some(GIMBAL_DEVICE_INFORMATION_DATA::ID),
33477 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::NAME => {
33478 Some(UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID)
33479 }
33480 SMART_BATTERY_INFO_DATA::NAME => Some(SMART_BATTERY_INFO_DATA::ID),
33481 ESC_STATUS_DATA::NAME => Some(ESC_STATUS_DATA::ID),
33482 COLLISION_DATA::NAME => Some(COLLISION_DATA::ID),
33483 LOGGING_DATA_DATA::NAME => Some(LOGGING_DATA_DATA::ID),
33484 GPS_INPUT_DATA::NAME => Some(GPS_INPUT_DATA::ID),
33485 HOME_POSITION_DATA::NAME => Some(HOME_POSITION_DATA::ID),
33486 PARAM_EXT_REQUEST_READ_DATA::NAME => Some(PARAM_EXT_REQUEST_READ_DATA::ID),
33487 LOG_REQUEST_LIST_DATA::NAME => Some(LOG_REQUEST_LIST_DATA::ID),
33488 ACTUATOR_OUTPUT_STATUS_DATA::NAME => Some(ACTUATOR_OUTPUT_STATUS_DATA::ID),
33489 OBSTACLE_DISTANCE_DATA::NAME => Some(OBSTACLE_DISTANCE_DATA::ID),
33490 WIND_COV_DATA::NAME => Some(WIND_COV_DATA::ID),
33491 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::NAME => Some(UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID),
33492 UAVIONIX_ADSB_OUT_STATUS_DATA::NAME => Some(UAVIONIX_ADSB_OUT_STATUS_DATA::ID),
33493 HIGH_LATENCY2_DATA::NAME => Some(HIGH_LATENCY2_DATA::ID),
33494 GIMBAL_DEVICE_SET_ATTITUDE_DATA::NAME => Some(GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID),
33495 PARAM_EXT_ACK_DATA::NAME => Some(PARAM_EXT_ACK_DATA::ID),
33496 SAFETY_SET_ALLOWED_AREA_DATA::NAME => Some(SAFETY_SET_ALLOWED_AREA_DATA::ID),
33497 FENCE_STATUS_DATA::NAME => Some(FENCE_STATUS_DATA::ID),
33498 WINCH_STATUS_DATA::NAME => Some(WINCH_STATUS_DATA::ID),
33499 ESC_INFO_DATA::NAME => Some(ESC_INFO_DATA::ID),
33500 MISSION_REQUEST_PARTIAL_LIST_DATA::NAME => Some(MISSION_REQUEST_PARTIAL_LIST_DATA::ID),
33501 NAV_CONTROLLER_OUTPUT_DATA::NAME => Some(NAV_CONTROLLER_OUTPUT_DATA::ID),
33502 HIL_OPTICAL_FLOW_DATA::NAME => Some(HIL_OPTICAL_FLOW_DATA::ID),
33503 LOG_DATA_DATA::NAME => Some(LOG_DATA_DATA::ID),
33504 HIL_STATE_QUATERNION_DATA::NAME => Some(HIL_STATE_QUATERNION_DATA::ID),
33505 CURRENT_MODE_DATA::NAME => Some(CURRENT_MODE_DATA::ID),
33506 WHEEL_DISTANCE_DATA::NAME => Some(WHEEL_DISTANCE_DATA::ID),
33507 OPTICAL_FLOW_DATA::NAME => Some(OPTICAL_FLOW_DATA::ID),
33508 CHANGE_OPERATOR_CONTROL_DATA::NAME => Some(CHANGE_OPERATOR_CONTROL_DATA::ID),
33509 VIBRATION_DATA::NAME => Some(VIBRATION_DATA::ID),
33510 CAMERA_FOV_STATUS_DATA::NAME => Some(CAMERA_FOV_STATUS_DATA::ID),
33511 MISSION_COUNT_DATA::NAME => Some(MISSION_COUNT_DATA::ID),
33512 OPEN_DRONE_ID_SYSTEM_DATA::NAME => Some(OPEN_DRONE_ID_SYSTEM_DATA::ID),
33513 ATTITUDE_QUATERNION_COV_DATA::NAME => Some(ATTITUDE_QUATERNION_COV_DATA::ID),
33514 POSITION_TARGET_GLOBAL_INT_DATA::NAME => Some(POSITION_TARGET_GLOBAL_INT_DATA::ID),
33515 SET_ACTUATOR_CONTROL_TARGET_DATA::NAME => Some(SET_ACTUATOR_CONTROL_TARGET_DATA::ID),
33516 CELLULAR_STATUS_DATA::NAME => Some(CELLULAR_STATUS_DATA::ID),
33517 COMPONENT_INFORMATION_DATA::NAME => Some(COMPONENT_INFORMATION_DATA::ID),
33518 RADIO_STATUS_DATA::NAME => Some(RADIO_STATUS_DATA::ID),
33519 TIMESYNC_DATA::NAME => Some(TIMESYNC_DATA::ID),
33520 GIMBAL_MANAGER_STATUS_DATA::NAME => Some(GIMBAL_MANAGER_STATUS_DATA::ID),
33521 COMMAND_CANCEL_DATA::NAME => Some(COMMAND_CANCEL_DATA::ID),
33522 HIL_ACTUATOR_CONTROLS_DATA::NAME => Some(HIL_ACTUATOR_CONTROLS_DATA::ID),
33523 NAMED_VALUE_INT_DATA::NAME => Some(NAMED_VALUE_INT_DATA::ID),
33524 DEBUG_FLOAT_ARRAY_DATA::NAME => Some(DEBUG_FLOAT_ARRAY_DATA::ID),
33525 OPEN_DRONE_ID_BASIC_ID_DATA::NAME => Some(OPEN_DRONE_ID_BASIC_ID_DATA::ID),
33526 COMPONENT_METADATA_DATA::NAME => Some(COMPONENT_METADATA_DATA::ID),
33527 LINK_NODE_STATUS_DATA::NAME => Some(LINK_NODE_STATUS_DATA::ID),
33528 LOCAL_POSITION_NED_COV_DATA::NAME => Some(LOCAL_POSITION_NED_COV_DATA::ID),
33529 CANFD_FRAME_DATA::NAME => Some(CANFD_FRAME_DATA::ID),
33530 OPTICAL_FLOW_RAD_DATA::NAME => Some(OPTICAL_FLOW_RAD_DATA::ID),
33531 PLAY_TUNE_DATA::NAME => Some(PLAY_TUNE_DATA::ID),
33532 COMPONENT_INFORMATION_BASIC_DATA::NAME => Some(COMPONENT_INFORMATION_BASIC_DATA::ID),
33533 OPEN_DRONE_ID_SELF_ID_DATA::NAME => Some(OPEN_DRONE_ID_SELF_ID_DATA::ID),
33534 HEARTBEAT_DATA::NAME => Some(HEARTBEAT_DATA::ID),
33535 EVENT_DATA::NAME => Some(EVENT_DATA::ID),
33536 OPEN_DRONE_ID_OPERATOR_ID_DATA::NAME => Some(OPEN_DRONE_ID_OPERATOR_ID_DATA::ID),
33537 AVAILABLE_MODES_DATA::NAME => Some(AVAILABLE_MODES_DATA::ID),
33538 SET_HOME_POSITION_DATA::NAME => Some(SET_HOME_POSITION_DATA::ID),
33539 FUEL_STATUS_DATA::NAME => Some(FUEL_STATUS_DATA::ID),
33540 OPEN_DRONE_ID_MESSAGE_PACK_DATA::NAME => Some(OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID),
33541 COMMAND_LONG_DATA::NAME => Some(COMMAND_LONG_DATA::ID),
33542 GPS_RTK_DATA::NAME => Some(GPS_RTK_DATA::ID),
33543 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::NAME => {
33544 Some(UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID)
33545 }
33546 CAN_FILTER_MODIFY_DATA::NAME => Some(CAN_FILTER_MODIFY_DATA::ID),
33547 EXTENDED_SYS_STATE_DATA::NAME => Some(EXTENDED_SYS_STATE_DATA::ID),
33548 UAVIONIX_ADSB_GET_DATA::NAME => Some(UAVIONIX_ADSB_GET_DATA::ID),
33549 SUPPORTED_TUNES_DATA::NAME => Some(SUPPORTED_TUNES_DATA::ID),
33550 DATA_TRANSMISSION_HANDSHAKE_DATA::NAME => Some(DATA_TRANSMISSION_HANDSHAKE_DATA::ID),
33551 PARAM_EXT_SET_DATA::NAME => Some(PARAM_EXT_SET_DATA::ID),
33552 CAMERA_IMAGE_CAPTURED_DATA::NAME => Some(CAMERA_IMAGE_CAPTURED_DATA::ID),
33553 REQUEST_EVENT_DATA::NAME => Some(REQUEST_EVENT_DATA::ID),
33554 GLOBAL_POSITION_INT_COV_DATA::NAME => Some(GLOBAL_POSITION_INT_COV_DATA::ID),
33555 PARAM_VALUE_DATA::NAME => Some(PARAM_VALUE_DATA::ID),
33556 MAG_CAL_REPORT_DATA::NAME => Some(MAG_CAL_REPORT_DATA::ID),
33557 MESSAGE_INTERVAL_DATA::NAME => Some(MESSAGE_INTERVAL_DATA::ID),
33558 PARAM_MAP_RC_DATA::NAME => Some(PARAM_MAP_RC_DATA::ID),
33559 STATUSTEXT_DATA::NAME => Some(STATUSTEXT_DATA::ID),
33560 CAMERA_TRACKING_GEO_STATUS_DATA::NAME => Some(CAMERA_TRACKING_GEO_STATUS_DATA::ID),
33561 GPS_INJECT_DATA_DATA::NAME => Some(GPS_INJECT_DATA_DATA::ID),
33562 VFR_HUD_DATA::NAME => Some(VFR_HUD_DATA::ID),
33563 MISSION_ITEM_INT_DATA::NAME => Some(MISSION_ITEM_INT_DATA::ID),
33564 ISBD_LINK_STATUS_DATA::NAME => Some(ISBD_LINK_STATUS_DATA::ID),
33565 PLAY_TUNE_V2_DATA::NAME => Some(PLAY_TUNE_V2_DATA::ID),
33566 CAMERA_SETTINGS_DATA::NAME => Some(CAMERA_SETTINGS_DATA::ID),
33567 MISSION_CLEAR_ALL_DATA::NAME => Some(MISSION_CLEAR_ALL_DATA::ID),
33568 MANUAL_SETPOINT_DATA::NAME => Some(MANUAL_SETPOINT_DATA::ID),
33569 MISSION_SET_CURRENT_DATA::NAME => Some(MISSION_SET_CURRENT_DATA::ID),
33570 HIL_GPS_DATA::NAME => Some(HIL_GPS_DATA::ID),
33571 REQUEST_DATA_STREAM_DATA::NAME => Some(REQUEST_DATA_STREAM_DATA::ID),
33572 HIGH_LATENCY_DATA::NAME => Some(HIGH_LATENCY_DATA::ID),
33573 FLIGHT_INFORMATION_DATA::NAME => Some(FLIGHT_INFORMATION_DATA::ID),
33574 SERIAL_CONTROL_DATA::NAME => Some(SERIAL_CONTROL_DATA::ID),
33575 COMMAND_INT_DATA::NAME => Some(COMMAND_INT_DATA::ID),
33576 CAMERA_INFORMATION_DATA::NAME => Some(CAMERA_INFORMATION_DATA::ID),
33577 SIM_STATE_DATA::NAME => Some(SIM_STATE_DATA::ID),
33578 GPS2_RTK_DATA::NAME => Some(GPS2_RTK_DATA::ID),
33579 SERVO_OUTPUT_RAW_DATA::NAME => Some(SERVO_OUTPUT_RAW_DATA::ID),
33580 AUTOPILOT_VERSION_DATA::NAME => Some(AUTOPILOT_VERSION_DATA::ID),
33581 UAVCAN_NODE_STATUS_DATA::NAME => Some(UAVCAN_NODE_STATUS_DATA::ID),
33582 RAW_PRESSURE_DATA::NAME => Some(RAW_PRESSURE_DATA::ID),
33583 VIDEO_STREAM_STATUS_DATA::NAME => Some(VIDEO_STREAM_STATUS_DATA::ID),
33584 BUTTON_CHANGE_DATA::NAME => Some(BUTTON_CHANGE_DATA::ID),
33585 PROTOCOL_VERSION_DATA::NAME => Some(PROTOCOL_VERSION_DATA::ID),
33586 DISTANCE_SENSOR_DATA::NAME => Some(DISTANCE_SENSOR_DATA::ID),
33587 GIMBAL_MANAGER_SET_ATTITUDE_DATA::NAME => Some(GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID),
33588 RC_CHANNELS_DATA::NAME => Some(RC_CHANNELS_DATA::ID),
33589 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::NAME => Some(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID),
33590 ATTITUDE_QUATERNION_DATA::NAME => Some(ATTITUDE_QUATERNION_DATA::ID),
33591 PARAM_REQUEST_READ_DATA::NAME => Some(PARAM_REQUEST_READ_DATA::ID),
33592 SCALED_PRESSURE3_DATA::NAME => Some(SCALED_PRESSURE3_DATA::ID),
33593 GIMBAL_MANAGER_INFORMATION_DATA::NAME => Some(GIMBAL_MANAGER_INFORMATION_DATA::ID),
33594 SETUP_SIGNING_DATA::NAME => Some(SETUP_SIGNING_DATA::ID),
33595 LOG_REQUEST_DATA_DATA::NAME => Some(LOG_REQUEST_DATA_DATA::ID),
33596 UAVIONIX_ADSB_OUT_CONTROL_DATA::NAME => Some(UAVIONIX_ADSB_OUT_CONTROL_DATA::ID),
33597 MISSION_ITEM_REACHED_DATA::NAME => Some(MISSION_ITEM_REACHED_DATA::ID),
33598 SET_POSITION_TARGET_GLOBAL_INT_DATA::NAME => {
33599 Some(SET_POSITION_TARGET_GLOBAL_INT_DATA::ID)
33600 }
33601 RESPONSE_EVENT_ERROR_DATA::NAME => Some(RESPONSE_EVENT_ERROR_DATA::ID),
33602 CURRENT_EVENT_SEQUENCE_DATA::NAME => Some(CURRENT_EVENT_SEQUENCE_DATA::ID),
33603 CAN_FRAME_DATA::NAME => Some(CAN_FRAME_DATA::ID),
33604 MOUNT_ORIENTATION_DATA::NAME => Some(MOUNT_ORIENTATION_DATA::ID),
33605 ILLUMINATOR_STATUS_DATA::NAME => Some(ILLUMINATOR_STATUS_DATA::ID),
33606 CHANGE_OPERATOR_CONTROL_ACK_DATA::NAME => Some(CHANGE_OPERATOR_CONTROL_ACK_DATA::ID),
33607 GIMBAL_MANAGER_SET_PITCHYAW_DATA::NAME => Some(GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID),
33608 OPEN_DRONE_ID_ARM_STATUS_DATA::NAME => Some(OPEN_DRONE_ID_ARM_STATUS_DATA::ID),
33609 UTM_GLOBAL_POSITION_DATA::NAME => Some(UTM_GLOBAL_POSITION_DATA::ID),
33610 RC_CHANNELS_OVERRIDE_DATA::NAME => Some(RC_CHANNELS_OVERRIDE_DATA::ID),
33611 SCALED_IMU_DATA::NAME => Some(SCALED_IMU_DATA::ID),
33612 DATA_STREAM_DATA::NAME => Some(DATA_STREAM_DATA::ID),
33613 LOG_ENTRY_DATA::NAME => Some(LOG_ENTRY_DATA::ID),
33614 PING_DATA::NAME => Some(PING_DATA::ID),
33615 POSITION_TARGET_LOCAL_NED_DATA::NAME => Some(POSITION_TARGET_LOCAL_NED_DATA::ID),
33616 SCALED_IMU2_DATA::NAME => Some(SCALED_IMU2_DATA::ID),
33617 GPS_RTCM_DATA_DATA::NAME => Some(GPS_RTCM_DATA_DATA::ID),
33618 SET_MODE_DATA::NAME => Some(SET_MODE_DATA::ID),
33619 ESTIMATOR_STATUS_DATA::NAME => Some(ESTIMATOR_STATUS_DATA::ID),
33620 HIL_STATE_DATA::NAME => Some(HIL_STATE_DATA::ID),
33621 SYSTEM_TIME_DATA::NAME => Some(SYSTEM_TIME_DATA::ID),
33622 STORAGE_INFORMATION_DATA::NAME => Some(STORAGE_INFORMATION_DATA::ID),
33623 BATTERY_INFO_DATA::NAME => Some(BATTERY_INFO_DATA::ID),
33624 SET_ATTITUDE_TARGET_DATA::NAME => Some(SET_ATTITUDE_TARGET_DATA::ID),
33625 HIL_RC_INPUTS_RAW_DATA::NAME => Some(HIL_RC_INPUTS_RAW_DATA::ID),
33626 CAMERA_TRIGGER_DATA::NAME => Some(CAMERA_TRIGGER_DATA::ID),
33627 TIME_ESTIMATE_TO_TARGET_DATA::NAME => Some(TIME_ESTIMATE_TO_TARGET_DATA::ID),
33628 HIL_SENSOR_DATA::NAME => Some(HIL_SENSOR_DATA::ID),
33629 MISSION_REQUEST_INT_DATA::NAME => Some(MISSION_REQUEST_INT_DATA::ID),
33630 TERRAIN_REPORT_DATA::NAME => Some(TERRAIN_REPORT_DATA::ID),
33631 BATTERY_STATUS_DATA::NAME => Some(BATTERY_STATUS_DATA::ID),
33632 GPS_RAW_INT_DATA::NAME => Some(GPS_RAW_INT_DATA::ID),
33633 VISION_POSITION_ESTIMATE_DATA::NAME => Some(VISION_POSITION_ESTIMATE_DATA::ID),
33634 CELLULAR_CONFIG_DATA::NAME => Some(CELLULAR_CONFIG_DATA::ID),
33635 SET_POSITION_TARGET_LOCAL_NED_DATA::NAME => {
33636 Some(SET_POSITION_TARGET_LOCAL_NED_DATA::ID)
33637 }
33638 GPS_GLOBAL_ORIGIN_DATA::NAME => Some(GPS_GLOBAL_ORIGIN_DATA::ID),
33639 RC_CHANNELS_SCALED_DATA::NAME => Some(RC_CHANNELS_SCALED_DATA::ID),
33640 ATTITUDE_DATA::NAME => Some(ATTITUDE_DATA::ID),
33641 GPS_STATUS_DATA::NAME => Some(GPS_STATUS_DATA::ID),
33642 CONTROL_SYSTEM_STATE_DATA::NAME => Some(CONTROL_SYSTEM_STATE_DATA::ID),
33643 PARAM_EXT_REQUEST_LIST_DATA::NAME => Some(PARAM_EXT_REQUEST_LIST_DATA::ID),
33644 VIDEO_STREAM_INFORMATION_DATA::NAME => Some(VIDEO_STREAM_INFORMATION_DATA::ID),
33645 RESOURCE_REQUEST_DATA::NAME => Some(RESOURCE_REQUEST_DATA::ID),
33646 HIGHRES_IMU_DATA::NAME => Some(HIGHRES_IMU_DATA::ID),
33647 HYGROMETER_SENSOR_DATA::NAME => Some(HYGROMETER_SENSOR_DATA::ID),
33648 MISSION_CURRENT_DATA::NAME => Some(MISSION_CURRENT_DATA::ID),
33649 AVAILABLE_MODES_MONITOR_DATA::NAME => Some(AVAILABLE_MODES_MONITOR_DATA::ID),
33650 POWER_STATUS_DATA::NAME => Some(POWER_STATUS_DATA::ID),
33651 RAW_RPM_DATA::NAME => Some(RAW_RPM_DATA::ID),
33652 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::NAME => {
33653 Some(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID)
33654 }
33655 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::NAME => {
33656 Some(UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID)
33657 }
33658 LOCAL_POSITION_NED_DATA::NAME => Some(LOCAL_POSITION_NED_DATA::ID),
33659 RAW_IMU_DATA::NAME => Some(RAW_IMU_DATA::ID),
33660 PARAM_SET_DATA::NAME => Some(PARAM_SET_DATA::ID),
33661 MISSION_REQUEST_DATA::NAME => Some(MISSION_REQUEST_DATA::ID),
33662 SAFETY_ALLOWED_AREA_DATA::NAME => Some(SAFETY_ALLOWED_AREA_DATA::ID),
33663 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::NAME => {
33664 Some(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID)
33665 }
33666 GLOBAL_POSITION_INT_DATA::NAME => Some(GLOBAL_POSITION_INT_DATA::ID),
33667 GLOBAL_VISION_POSITION_ESTIMATE_DATA::NAME => {
33668 Some(GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID)
33669 }
33670 TUNNEL_DATA::NAME => Some(TUNNEL_DATA::ID),
33671 PARAM_EXT_VALUE_DATA::NAME => Some(PARAM_EXT_VALUE_DATA::ID),
33672 TERRAIN_CHECK_DATA::NAME => Some(TERRAIN_CHECK_DATA::ID),
33673 COMMAND_ACK_DATA::NAME => Some(COMMAND_ACK_DATA::ID),
33674 MISSION_ITEM_DATA::NAME => Some(MISSION_ITEM_DATA::ID),
33675 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::NAME => {
33676 Some(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID)
33677 }
33678 DEBUG_DATA::NAME => Some(DEBUG_DATA::ID),
33679 GPS2_RAW_DATA::NAME => Some(GPS2_RAW_DATA::ID),
33680 ONBOARD_COMPUTER_STATUS_DATA::NAME => Some(ONBOARD_COMPUTER_STATUS_DATA::ID),
33681 ATTITUDE_TARGET_DATA::NAME => Some(ATTITUDE_TARGET_DATA::ID),
33682 RC_CHANNELS_RAW_DATA::NAME => Some(RC_CHANNELS_RAW_DATA::ID),
33683 ODOMETRY_DATA::NAME => Some(ODOMETRY_DATA::ID),
33684 VISION_SPEED_ESTIMATE_DATA::NAME => Some(VISION_SPEED_ESTIMATE_DATA::ID),
33685 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::NAME => {
33686 Some(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID)
33687 }
33688 ALTITUDE_DATA::NAME => Some(ALTITUDE_DATA::ID),
33689 OPEN_DRONE_ID_AUTHENTICATION_DATA::NAME => Some(OPEN_DRONE_ID_AUTHENTICATION_DATA::ID),
33690 PARAM_REQUEST_LIST_DATA::NAME => Some(PARAM_REQUEST_LIST_DATA::ID),
33691 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::NAME => {
33692 Some(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID)
33693 }
33694 _ => None,
33695 }
33696 }
33697 fn default_message_from_id(id: u32) -> Option<Self> {
33698 match id {
33699 ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::ACTUATOR_CONTROL_TARGET(
33700 ACTUATOR_CONTROL_TARGET_DATA::default(),
33701 )),
33702 LOG_ERASE_DATA::ID => Some(Self::LOG_ERASE(LOG_ERASE_DATA::default())),
33703 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_IMAGE_STATUS(
33704 CAMERA_TRACKING_IMAGE_STATUS_DATA::default(),
33705 )),
33706 MISSION_WRITE_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_WRITE_PARTIAL_LIST(
33707 MISSION_WRITE_PARTIAL_LIST_DATA::default(),
33708 )),
33709 SCALED_PRESSURE_DATA::ID => {
33710 Some(Self::SCALED_PRESSURE(SCALED_PRESSURE_DATA::default()))
33711 }
33712 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
33713 Some(Self::TRAJECTORY_REPRESENTATION_BEZIER(
33714 TRAJECTORY_REPRESENTATION_BEZIER_DATA::default(),
33715 ))
33716 }
33717 ORBIT_EXECUTION_STATUS_DATA::ID => Some(Self::ORBIT_EXECUTION_STATUS(
33718 ORBIT_EXECUTION_STATUS_DATA::default(),
33719 )),
33720 AUTH_KEY_DATA::ID => Some(Self::AUTH_KEY(AUTH_KEY_DATA::default())),
33721 FILE_TRANSFER_PROTOCOL_DATA::ID => Some(Self::FILE_TRANSFER_PROTOCOL(
33722 FILE_TRANSFER_PROTOCOL_DATA::default(),
33723 )),
33724 SYS_STATUS_DATA::ID => Some(Self::SYS_STATUS(SYS_STATUS_DATA::default())),
33725 LOG_REQUEST_END_DATA::ID => {
33726 Some(Self::LOG_REQUEST_END(LOG_REQUEST_END_DATA::default()))
33727 }
33728 TERRAIN_DATA_DATA::ID => Some(Self::TERRAIN_DATA(TERRAIN_DATA_DATA::default())),
33729 LOGGING_DATA_ACKED_DATA::ID => {
33730 Some(Self::LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA::default()))
33731 }
33732 NAMED_VALUE_FLOAT_DATA::ID => {
33733 Some(Self::NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA::default()))
33734 }
33735 LANDING_TARGET_DATA::ID => Some(Self::LANDING_TARGET(LANDING_TARGET_DATA::default())),
33736 ATT_POS_MOCAP_DATA::ID => Some(Self::ATT_POS_MOCAP(ATT_POS_MOCAP_DATA::default())),
33737 SCALED_IMU3_DATA::ID => Some(Self::SCALED_IMU3(SCALED_IMU3_DATA::default())),
33738 MEMORY_VECT_DATA::ID => Some(Self::MEMORY_VECT(MEMORY_VECT_DATA::default())),
33739 TERRAIN_REQUEST_DATA::ID => {
33740 Some(Self::TERRAIN_REQUEST(TERRAIN_REQUEST_DATA::default()))
33741 }
33742 V2_EXTENSION_DATA::ID => Some(Self::V2_EXTENSION(V2_EXTENSION_DATA::default())),
33743 DEBUG_VECT_DATA::ID => Some(Self::DEBUG_VECT(DEBUG_VECT_DATA::default())),
33744 MANUAL_CONTROL_DATA::ID => Some(Self::MANUAL_CONTROL(MANUAL_CONTROL_DATA::default())),
33745 AIS_VESSEL_DATA::ID => Some(Self::AIS_VESSEL(AIS_VESSEL_DATA::default())),
33746 UAVCAN_NODE_INFO_DATA::ID => {
33747 Some(Self::UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA::default()))
33748 }
33749 SET_GPS_GLOBAL_ORIGIN_DATA::ID => Some(Self::SET_GPS_GLOBAL_ORIGIN(
33750 SET_GPS_GLOBAL_ORIGIN_DATA::default(),
33751 )),
33752 SCALED_PRESSURE2_DATA::ID => {
33753 Some(Self::SCALED_PRESSURE2(SCALED_PRESSURE2_DATA::default()))
33754 }
33755 CAMERA_CAPTURE_STATUS_DATA::ID => Some(Self::CAMERA_CAPTURE_STATUS(
33756 CAMERA_CAPTURE_STATUS_DATA::default(),
33757 )),
33758 WIFI_CONFIG_AP_DATA::ID => Some(Self::WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA::default())),
33759 MISSION_REQUEST_LIST_DATA::ID => Some(Self::MISSION_REQUEST_LIST(
33760 MISSION_REQUEST_LIST_DATA::default(),
33761 )),
33762 MISSION_ACK_DATA::ID => Some(Self::MISSION_ACK(MISSION_ACK_DATA::default())),
33763 ENCAPSULATED_DATA_DATA::ID => {
33764 Some(Self::ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA::default()))
33765 }
33766 UAVIONIX_ADSB_OUT_CFG_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CFG(
33767 UAVIONIX_ADSB_OUT_CFG_DATA::default(),
33768 )),
33769 EFI_STATUS_DATA::ID => Some(Self::EFI_STATUS(EFI_STATUS_DATA::default())),
33770 OPEN_DRONE_ID_LOCATION_DATA::ID => Some(Self::OPEN_DRONE_ID_LOCATION(
33771 OPEN_DRONE_ID_LOCATION_DATA::default(),
33772 )),
33773 CAMERA_THERMAL_RANGE_DATA::ID => Some(Self::CAMERA_THERMAL_RANGE(
33774 CAMERA_THERMAL_RANGE_DATA::default(),
33775 )),
33776 LOGGING_ACK_DATA::ID => Some(Self::LOGGING_ACK(LOGGING_ACK_DATA::default())),
33777 HIL_CONTROLS_DATA::ID => Some(Self::HIL_CONTROLS(HIL_CONTROLS_DATA::default())),
33778 GENERATOR_STATUS_DATA::ID => {
33779 Some(Self::GENERATOR_STATUS(GENERATOR_STATUS_DATA::default()))
33780 }
33781 FOLLOW_TARGET_DATA::ID => Some(Self::FOLLOW_TARGET(FOLLOW_TARGET_DATA::default())),
33782 VICON_POSITION_ESTIMATE_DATA::ID => Some(Self::VICON_POSITION_ESTIMATE(
33783 VICON_POSITION_ESTIMATE_DATA::default(),
33784 )),
33785 ADSB_VEHICLE_DATA::ID => Some(Self::ADSB_VEHICLE(ADSB_VEHICLE_DATA::default())),
33786 GIMBAL_DEVICE_INFORMATION_DATA::ID => Some(Self::GIMBAL_DEVICE_INFORMATION(
33787 GIMBAL_DEVICE_INFORMATION_DATA::default(),
33788 )),
33789 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID => {
33790 Some(Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(
33791 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::default(),
33792 ))
33793 }
33794 SMART_BATTERY_INFO_DATA::ID => {
33795 Some(Self::SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA::default()))
33796 }
33797 ESC_STATUS_DATA::ID => Some(Self::ESC_STATUS(ESC_STATUS_DATA::default())),
33798 COLLISION_DATA::ID => Some(Self::COLLISION(COLLISION_DATA::default())),
33799 LOGGING_DATA_DATA::ID => Some(Self::LOGGING_DATA(LOGGING_DATA_DATA::default())),
33800 GPS_INPUT_DATA::ID => Some(Self::GPS_INPUT(GPS_INPUT_DATA::default())),
33801 HOME_POSITION_DATA::ID => Some(Self::HOME_POSITION(HOME_POSITION_DATA::default())),
33802 PARAM_EXT_REQUEST_READ_DATA::ID => Some(Self::PARAM_EXT_REQUEST_READ(
33803 PARAM_EXT_REQUEST_READ_DATA::default(),
33804 )),
33805 LOG_REQUEST_LIST_DATA::ID => {
33806 Some(Self::LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA::default()))
33807 }
33808 ACTUATOR_OUTPUT_STATUS_DATA::ID => Some(Self::ACTUATOR_OUTPUT_STATUS(
33809 ACTUATOR_OUTPUT_STATUS_DATA::default(),
33810 )),
33811 OBSTACLE_DISTANCE_DATA::ID => {
33812 Some(Self::OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA::default()))
33813 }
33814 WIND_COV_DATA::ID => Some(Self::WIND_COV(WIND_COV_DATA::default())),
33815 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_DYNAMIC(
33816 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::default(),
33817 )),
33818 UAVIONIX_ADSB_OUT_STATUS_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_STATUS(
33819 UAVIONIX_ADSB_OUT_STATUS_DATA::default(),
33820 )),
33821 HIGH_LATENCY2_DATA::ID => Some(Self::HIGH_LATENCY2(HIGH_LATENCY2_DATA::default())),
33822 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_DEVICE_SET_ATTITUDE(
33823 GIMBAL_DEVICE_SET_ATTITUDE_DATA::default(),
33824 )),
33825 PARAM_EXT_ACK_DATA::ID => Some(Self::PARAM_EXT_ACK(PARAM_EXT_ACK_DATA::default())),
33826 SAFETY_SET_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_SET_ALLOWED_AREA(
33827 SAFETY_SET_ALLOWED_AREA_DATA::default(),
33828 )),
33829 FENCE_STATUS_DATA::ID => Some(Self::FENCE_STATUS(FENCE_STATUS_DATA::default())),
33830 WINCH_STATUS_DATA::ID => Some(Self::WINCH_STATUS(WINCH_STATUS_DATA::default())),
33831 ESC_INFO_DATA::ID => Some(Self::ESC_INFO(ESC_INFO_DATA::default())),
33832 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_REQUEST_PARTIAL_LIST(
33833 MISSION_REQUEST_PARTIAL_LIST_DATA::default(),
33834 )),
33835 NAV_CONTROLLER_OUTPUT_DATA::ID => Some(Self::NAV_CONTROLLER_OUTPUT(
33836 NAV_CONTROLLER_OUTPUT_DATA::default(),
33837 )),
33838 HIL_OPTICAL_FLOW_DATA::ID => {
33839 Some(Self::HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA::default()))
33840 }
33841 LOG_DATA_DATA::ID => Some(Self::LOG_DATA(LOG_DATA_DATA::default())),
33842 HIL_STATE_QUATERNION_DATA::ID => Some(Self::HIL_STATE_QUATERNION(
33843 HIL_STATE_QUATERNION_DATA::default(),
33844 )),
33845 CURRENT_MODE_DATA::ID => Some(Self::CURRENT_MODE(CURRENT_MODE_DATA::default())),
33846 WHEEL_DISTANCE_DATA::ID => Some(Self::WHEEL_DISTANCE(WHEEL_DISTANCE_DATA::default())),
33847 OPTICAL_FLOW_DATA::ID => Some(Self::OPTICAL_FLOW(OPTICAL_FLOW_DATA::default())),
33848 CHANGE_OPERATOR_CONTROL_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL(
33849 CHANGE_OPERATOR_CONTROL_DATA::default(),
33850 )),
33851 VIBRATION_DATA::ID => Some(Self::VIBRATION(VIBRATION_DATA::default())),
33852 CAMERA_FOV_STATUS_DATA::ID => {
33853 Some(Self::CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA::default()))
33854 }
33855 MISSION_COUNT_DATA::ID => Some(Self::MISSION_COUNT(MISSION_COUNT_DATA::default())),
33856 OPEN_DRONE_ID_SYSTEM_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM(
33857 OPEN_DRONE_ID_SYSTEM_DATA::default(),
33858 )),
33859 ATTITUDE_QUATERNION_COV_DATA::ID => Some(Self::ATTITUDE_QUATERNION_COV(
33860 ATTITUDE_QUATERNION_COV_DATA::default(),
33861 )),
33862 POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::POSITION_TARGET_GLOBAL_INT(
33863 POSITION_TARGET_GLOBAL_INT_DATA::default(),
33864 )),
33865 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::SET_ACTUATOR_CONTROL_TARGET(
33866 SET_ACTUATOR_CONTROL_TARGET_DATA::default(),
33867 )),
33868 CELLULAR_STATUS_DATA::ID => {
33869 Some(Self::CELLULAR_STATUS(CELLULAR_STATUS_DATA::default()))
33870 }
33871 COMPONENT_INFORMATION_DATA::ID => Some(Self::COMPONENT_INFORMATION(
33872 COMPONENT_INFORMATION_DATA::default(),
33873 )),
33874 RADIO_STATUS_DATA::ID => Some(Self::RADIO_STATUS(RADIO_STATUS_DATA::default())),
33875 TIMESYNC_DATA::ID => Some(Self::TIMESYNC(TIMESYNC_DATA::default())),
33876 GIMBAL_MANAGER_STATUS_DATA::ID => Some(Self::GIMBAL_MANAGER_STATUS(
33877 GIMBAL_MANAGER_STATUS_DATA::default(),
33878 )),
33879 COMMAND_CANCEL_DATA::ID => Some(Self::COMMAND_CANCEL(COMMAND_CANCEL_DATA::default())),
33880 HIL_ACTUATOR_CONTROLS_DATA::ID => Some(Self::HIL_ACTUATOR_CONTROLS(
33881 HIL_ACTUATOR_CONTROLS_DATA::default(),
33882 )),
33883 NAMED_VALUE_INT_DATA::ID => {
33884 Some(Self::NAMED_VALUE_INT(NAMED_VALUE_INT_DATA::default()))
33885 }
33886 DEBUG_FLOAT_ARRAY_DATA::ID => {
33887 Some(Self::DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA::default()))
33888 }
33889 OPEN_DRONE_ID_BASIC_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_BASIC_ID(
33890 OPEN_DRONE_ID_BASIC_ID_DATA::default(),
33891 )),
33892 COMPONENT_METADATA_DATA::ID => {
33893 Some(Self::COMPONENT_METADATA(COMPONENT_METADATA_DATA::default()))
33894 }
33895 LINK_NODE_STATUS_DATA::ID => {
33896 Some(Self::LINK_NODE_STATUS(LINK_NODE_STATUS_DATA::default()))
33897 }
33898 LOCAL_POSITION_NED_COV_DATA::ID => Some(Self::LOCAL_POSITION_NED_COV(
33899 LOCAL_POSITION_NED_COV_DATA::default(),
33900 )),
33901 CANFD_FRAME_DATA::ID => Some(Self::CANFD_FRAME(CANFD_FRAME_DATA::default())),
33902 OPTICAL_FLOW_RAD_DATA::ID => {
33903 Some(Self::OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA::default()))
33904 }
33905 PLAY_TUNE_DATA::ID => Some(Self::PLAY_TUNE(PLAY_TUNE_DATA::default())),
33906 COMPONENT_INFORMATION_BASIC_DATA::ID => Some(Self::COMPONENT_INFORMATION_BASIC(
33907 COMPONENT_INFORMATION_BASIC_DATA::default(),
33908 )),
33909 OPEN_DRONE_ID_SELF_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_SELF_ID(
33910 OPEN_DRONE_ID_SELF_ID_DATA::default(),
33911 )),
33912 HEARTBEAT_DATA::ID => Some(Self::HEARTBEAT(HEARTBEAT_DATA::default())),
33913 EVENT_DATA::ID => Some(Self::EVENT(EVENT_DATA::default())),
33914 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_OPERATOR_ID(
33915 OPEN_DRONE_ID_OPERATOR_ID_DATA::default(),
33916 )),
33917 AVAILABLE_MODES_DATA::ID => {
33918 Some(Self::AVAILABLE_MODES(AVAILABLE_MODES_DATA::default()))
33919 }
33920 SET_HOME_POSITION_DATA::ID => {
33921 Some(Self::SET_HOME_POSITION(SET_HOME_POSITION_DATA::default()))
33922 }
33923 FUEL_STATUS_DATA::ID => Some(Self::FUEL_STATUS(FUEL_STATUS_DATA::default())),
33924 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => Some(Self::OPEN_DRONE_ID_MESSAGE_PACK(
33925 OPEN_DRONE_ID_MESSAGE_PACK_DATA::default(),
33926 )),
33927 COMMAND_LONG_DATA::ID => Some(Self::COMMAND_LONG(COMMAND_LONG_DATA::default())),
33928 GPS_RTK_DATA::ID => Some(Self::GPS_RTK(GPS_RTK_DATA::default())),
33929 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID => {
33930 Some(Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(
33931 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::default(),
33932 ))
33933 }
33934 CAN_FILTER_MODIFY_DATA::ID => {
33935 Some(Self::CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA::default()))
33936 }
33937 EXTENDED_SYS_STATE_DATA::ID => {
33938 Some(Self::EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA::default()))
33939 }
33940 UAVIONIX_ADSB_GET_DATA::ID => {
33941 Some(Self::UAVIONIX_ADSB_GET(UAVIONIX_ADSB_GET_DATA::default()))
33942 }
33943 SUPPORTED_TUNES_DATA::ID => {
33944 Some(Self::SUPPORTED_TUNES(SUPPORTED_TUNES_DATA::default()))
33945 }
33946 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => Some(Self::DATA_TRANSMISSION_HANDSHAKE(
33947 DATA_TRANSMISSION_HANDSHAKE_DATA::default(),
33948 )),
33949 PARAM_EXT_SET_DATA::ID => Some(Self::PARAM_EXT_SET(PARAM_EXT_SET_DATA::default())),
33950 CAMERA_IMAGE_CAPTURED_DATA::ID => Some(Self::CAMERA_IMAGE_CAPTURED(
33951 CAMERA_IMAGE_CAPTURED_DATA::default(),
33952 )),
33953 REQUEST_EVENT_DATA::ID => Some(Self::REQUEST_EVENT(REQUEST_EVENT_DATA::default())),
33954 GLOBAL_POSITION_INT_COV_DATA::ID => Some(Self::GLOBAL_POSITION_INT_COV(
33955 GLOBAL_POSITION_INT_COV_DATA::default(),
33956 )),
33957 PARAM_VALUE_DATA::ID => Some(Self::PARAM_VALUE(PARAM_VALUE_DATA::default())),
33958 MAG_CAL_REPORT_DATA::ID => Some(Self::MAG_CAL_REPORT(MAG_CAL_REPORT_DATA::default())),
33959 MESSAGE_INTERVAL_DATA::ID => {
33960 Some(Self::MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA::default()))
33961 }
33962 PARAM_MAP_RC_DATA::ID => Some(Self::PARAM_MAP_RC(PARAM_MAP_RC_DATA::default())),
33963 STATUSTEXT_DATA::ID => Some(Self::STATUSTEXT(STATUSTEXT_DATA::default())),
33964 CAMERA_TRACKING_GEO_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_GEO_STATUS(
33965 CAMERA_TRACKING_GEO_STATUS_DATA::default(),
33966 )),
33967 GPS_INJECT_DATA_DATA::ID => {
33968 Some(Self::GPS_INJECT_DATA(GPS_INJECT_DATA_DATA::default()))
33969 }
33970 VFR_HUD_DATA::ID => Some(Self::VFR_HUD(VFR_HUD_DATA::default())),
33971 MISSION_ITEM_INT_DATA::ID => {
33972 Some(Self::MISSION_ITEM_INT(MISSION_ITEM_INT_DATA::default()))
33973 }
33974 ISBD_LINK_STATUS_DATA::ID => {
33975 Some(Self::ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA::default()))
33976 }
33977 PLAY_TUNE_V2_DATA::ID => Some(Self::PLAY_TUNE_V2(PLAY_TUNE_V2_DATA::default())),
33978 CAMERA_SETTINGS_DATA::ID => {
33979 Some(Self::CAMERA_SETTINGS(CAMERA_SETTINGS_DATA::default()))
33980 }
33981 MISSION_CLEAR_ALL_DATA::ID => {
33982 Some(Self::MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA::default()))
33983 }
33984 MANUAL_SETPOINT_DATA::ID => {
33985 Some(Self::MANUAL_SETPOINT(MANUAL_SETPOINT_DATA::default()))
33986 }
33987 MISSION_SET_CURRENT_DATA::ID => Some(Self::MISSION_SET_CURRENT(
33988 MISSION_SET_CURRENT_DATA::default(),
33989 )),
33990 HIL_GPS_DATA::ID => Some(Self::HIL_GPS(HIL_GPS_DATA::default())),
33991 REQUEST_DATA_STREAM_DATA::ID => Some(Self::REQUEST_DATA_STREAM(
33992 REQUEST_DATA_STREAM_DATA::default(),
33993 )),
33994 HIGH_LATENCY_DATA::ID => Some(Self::HIGH_LATENCY(HIGH_LATENCY_DATA::default())),
33995 FLIGHT_INFORMATION_DATA::ID => {
33996 Some(Self::FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA::default()))
33997 }
33998 SERIAL_CONTROL_DATA::ID => Some(Self::SERIAL_CONTROL(SERIAL_CONTROL_DATA::default())),
33999 COMMAND_INT_DATA::ID => Some(Self::COMMAND_INT(COMMAND_INT_DATA::default())),
34000 CAMERA_INFORMATION_DATA::ID => {
34001 Some(Self::CAMERA_INFORMATION(CAMERA_INFORMATION_DATA::default()))
34002 }
34003 SIM_STATE_DATA::ID => Some(Self::SIM_STATE(SIM_STATE_DATA::default())),
34004 GPS2_RTK_DATA::ID => Some(Self::GPS2_RTK(GPS2_RTK_DATA::default())),
34005 SERVO_OUTPUT_RAW_DATA::ID => {
34006 Some(Self::SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA::default()))
34007 }
34008 AUTOPILOT_VERSION_DATA::ID => {
34009 Some(Self::AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA::default()))
34010 }
34011 UAVCAN_NODE_STATUS_DATA::ID => {
34012 Some(Self::UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA::default()))
34013 }
34014 RAW_PRESSURE_DATA::ID => Some(Self::RAW_PRESSURE(RAW_PRESSURE_DATA::default())),
34015 VIDEO_STREAM_STATUS_DATA::ID => Some(Self::VIDEO_STREAM_STATUS(
34016 VIDEO_STREAM_STATUS_DATA::default(),
34017 )),
34018 BUTTON_CHANGE_DATA::ID => Some(Self::BUTTON_CHANGE(BUTTON_CHANGE_DATA::default())),
34019 PROTOCOL_VERSION_DATA::ID => {
34020 Some(Self::PROTOCOL_VERSION(PROTOCOL_VERSION_DATA::default()))
34021 }
34022 DISTANCE_SENSOR_DATA::ID => {
34023 Some(Self::DISTANCE_SENSOR(DISTANCE_SENSOR_DATA::default()))
34024 }
34025 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_ATTITUDE(
34026 GIMBAL_MANAGER_SET_ATTITUDE_DATA::default(),
34027 )),
34028 RC_CHANNELS_DATA::ID => Some(Self::RC_CHANNELS(RC_CHANNELS_DATA::default())),
34029 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM_UPDATE(
34030 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::default(),
34031 )),
34032 ATTITUDE_QUATERNION_DATA::ID => Some(Self::ATTITUDE_QUATERNION(
34033 ATTITUDE_QUATERNION_DATA::default(),
34034 )),
34035 PARAM_REQUEST_READ_DATA::ID => {
34036 Some(Self::PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA::default()))
34037 }
34038 SCALED_PRESSURE3_DATA::ID => {
34039 Some(Self::SCALED_PRESSURE3(SCALED_PRESSURE3_DATA::default()))
34040 }
34041 GIMBAL_MANAGER_INFORMATION_DATA::ID => Some(Self::GIMBAL_MANAGER_INFORMATION(
34042 GIMBAL_MANAGER_INFORMATION_DATA::default(),
34043 )),
34044 SETUP_SIGNING_DATA::ID => Some(Self::SETUP_SIGNING(SETUP_SIGNING_DATA::default())),
34045 LOG_REQUEST_DATA_DATA::ID => {
34046 Some(Self::LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA::default()))
34047 }
34048 UAVIONIX_ADSB_OUT_CONTROL_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CONTROL(
34049 UAVIONIX_ADSB_OUT_CONTROL_DATA::default(),
34050 )),
34051 MISSION_ITEM_REACHED_DATA::ID => Some(Self::MISSION_ITEM_REACHED(
34052 MISSION_ITEM_REACHED_DATA::default(),
34053 )),
34054 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::SET_POSITION_TARGET_GLOBAL_INT(
34055 SET_POSITION_TARGET_GLOBAL_INT_DATA::default(),
34056 )),
34057 RESPONSE_EVENT_ERROR_DATA::ID => Some(Self::RESPONSE_EVENT_ERROR(
34058 RESPONSE_EVENT_ERROR_DATA::default(),
34059 )),
34060 CURRENT_EVENT_SEQUENCE_DATA::ID => Some(Self::CURRENT_EVENT_SEQUENCE(
34061 CURRENT_EVENT_SEQUENCE_DATA::default(),
34062 )),
34063 CAN_FRAME_DATA::ID => Some(Self::CAN_FRAME(CAN_FRAME_DATA::default())),
34064 MOUNT_ORIENTATION_DATA::ID => {
34065 Some(Self::MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA::default()))
34066 }
34067 ILLUMINATOR_STATUS_DATA::ID => {
34068 Some(Self::ILLUMINATOR_STATUS(ILLUMINATOR_STATUS_DATA::default()))
34069 }
34070 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL_ACK(
34071 CHANGE_OPERATOR_CONTROL_ACK_DATA::default(),
34072 )),
34073 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_PITCHYAW(
34074 GIMBAL_MANAGER_SET_PITCHYAW_DATA::default(),
34075 )),
34076 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => Some(Self::OPEN_DRONE_ID_ARM_STATUS(
34077 OPEN_DRONE_ID_ARM_STATUS_DATA::default(),
34078 )),
34079 UTM_GLOBAL_POSITION_DATA::ID => Some(Self::UTM_GLOBAL_POSITION(
34080 UTM_GLOBAL_POSITION_DATA::default(),
34081 )),
34082 RC_CHANNELS_OVERRIDE_DATA::ID => Some(Self::RC_CHANNELS_OVERRIDE(
34083 RC_CHANNELS_OVERRIDE_DATA::default(),
34084 )),
34085 SCALED_IMU_DATA::ID => Some(Self::SCALED_IMU(SCALED_IMU_DATA::default())),
34086 DATA_STREAM_DATA::ID => Some(Self::DATA_STREAM(DATA_STREAM_DATA::default())),
34087 LOG_ENTRY_DATA::ID => Some(Self::LOG_ENTRY(LOG_ENTRY_DATA::default())),
34088 PING_DATA::ID => Some(Self::PING(PING_DATA::default())),
34089 POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::POSITION_TARGET_LOCAL_NED(
34090 POSITION_TARGET_LOCAL_NED_DATA::default(),
34091 )),
34092 SCALED_IMU2_DATA::ID => Some(Self::SCALED_IMU2(SCALED_IMU2_DATA::default())),
34093 GPS_RTCM_DATA_DATA::ID => Some(Self::GPS_RTCM_DATA(GPS_RTCM_DATA_DATA::default())),
34094 SET_MODE_DATA::ID => Some(Self::SET_MODE(SET_MODE_DATA::default())),
34095 ESTIMATOR_STATUS_DATA::ID => {
34096 Some(Self::ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA::default()))
34097 }
34098 HIL_STATE_DATA::ID => Some(Self::HIL_STATE(HIL_STATE_DATA::default())),
34099 SYSTEM_TIME_DATA::ID => Some(Self::SYSTEM_TIME(SYSTEM_TIME_DATA::default())),
34100 STORAGE_INFORMATION_DATA::ID => Some(Self::STORAGE_INFORMATION(
34101 STORAGE_INFORMATION_DATA::default(),
34102 )),
34103 BATTERY_INFO_DATA::ID => Some(Self::BATTERY_INFO(BATTERY_INFO_DATA::default())),
34104 SET_ATTITUDE_TARGET_DATA::ID => Some(Self::SET_ATTITUDE_TARGET(
34105 SET_ATTITUDE_TARGET_DATA::default(),
34106 )),
34107 HIL_RC_INPUTS_RAW_DATA::ID => {
34108 Some(Self::HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA::default()))
34109 }
34110 CAMERA_TRIGGER_DATA::ID => Some(Self::CAMERA_TRIGGER(CAMERA_TRIGGER_DATA::default())),
34111 TIME_ESTIMATE_TO_TARGET_DATA::ID => Some(Self::TIME_ESTIMATE_TO_TARGET(
34112 TIME_ESTIMATE_TO_TARGET_DATA::default(),
34113 )),
34114 HIL_SENSOR_DATA::ID => Some(Self::HIL_SENSOR(HIL_SENSOR_DATA::default())),
34115 MISSION_REQUEST_INT_DATA::ID => Some(Self::MISSION_REQUEST_INT(
34116 MISSION_REQUEST_INT_DATA::default(),
34117 )),
34118 TERRAIN_REPORT_DATA::ID => Some(Self::TERRAIN_REPORT(TERRAIN_REPORT_DATA::default())),
34119 BATTERY_STATUS_DATA::ID => Some(Self::BATTERY_STATUS(BATTERY_STATUS_DATA::default())),
34120 GPS_RAW_INT_DATA::ID => Some(Self::GPS_RAW_INT(GPS_RAW_INT_DATA::default())),
34121 VISION_POSITION_ESTIMATE_DATA::ID => Some(Self::VISION_POSITION_ESTIMATE(
34122 VISION_POSITION_ESTIMATE_DATA::default(),
34123 )),
34124 CELLULAR_CONFIG_DATA::ID => {
34125 Some(Self::CELLULAR_CONFIG(CELLULAR_CONFIG_DATA::default()))
34126 }
34127 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::SET_POSITION_TARGET_LOCAL_NED(
34128 SET_POSITION_TARGET_LOCAL_NED_DATA::default(),
34129 )),
34130 GPS_GLOBAL_ORIGIN_DATA::ID => {
34131 Some(Self::GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA::default()))
34132 }
34133 RC_CHANNELS_SCALED_DATA::ID => {
34134 Some(Self::RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA::default()))
34135 }
34136 ATTITUDE_DATA::ID => Some(Self::ATTITUDE(ATTITUDE_DATA::default())),
34137 GPS_STATUS_DATA::ID => Some(Self::GPS_STATUS(GPS_STATUS_DATA::default())),
34138 CONTROL_SYSTEM_STATE_DATA::ID => Some(Self::CONTROL_SYSTEM_STATE(
34139 CONTROL_SYSTEM_STATE_DATA::default(),
34140 )),
34141 PARAM_EXT_REQUEST_LIST_DATA::ID => Some(Self::PARAM_EXT_REQUEST_LIST(
34142 PARAM_EXT_REQUEST_LIST_DATA::default(),
34143 )),
34144 VIDEO_STREAM_INFORMATION_DATA::ID => Some(Self::VIDEO_STREAM_INFORMATION(
34145 VIDEO_STREAM_INFORMATION_DATA::default(),
34146 )),
34147 RESOURCE_REQUEST_DATA::ID => {
34148 Some(Self::RESOURCE_REQUEST(RESOURCE_REQUEST_DATA::default()))
34149 }
34150 HIGHRES_IMU_DATA::ID => Some(Self::HIGHRES_IMU(HIGHRES_IMU_DATA::default())),
34151 HYGROMETER_SENSOR_DATA::ID => {
34152 Some(Self::HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA::default()))
34153 }
34154 MISSION_CURRENT_DATA::ID => {
34155 Some(Self::MISSION_CURRENT(MISSION_CURRENT_DATA::default()))
34156 }
34157 AVAILABLE_MODES_MONITOR_DATA::ID => Some(Self::AVAILABLE_MODES_MONITOR(
34158 AVAILABLE_MODES_MONITOR_DATA::default(),
34159 )),
34160 POWER_STATUS_DATA::ID => Some(Self::POWER_STATUS(POWER_STATUS_DATA::default())),
34161 RAW_RPM_DATA::ID => Some(Self::RAW_RPM(RAW_RPM_DATA::default())),
34162 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
34163 Some(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(
34164 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::default(),
34165 ))
34166 }
34167 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(
34168 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::default(),
34169 )),
34170 LOCAL_POSITION_NED_DATA::ID => {
34171 Some(Self::LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA::default()))
34172 }
34173 RAW_IMU_DATA::ID => Some(Self::RAW_IMU(RAW_IMU_DATA::default())),
34174 PARAM_SET_DATA::ID => Some(Self::PARAM_SET(PARAM_SET_DATA::default())),
34175 MISSION_REQUEST_DATA::ID => {
34176 Some(Self::MISSION_REQUEST(MISSION_REQUEST_DATA::default()))
34177 }
34178 SAFETY_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_ALLOWED_AREA(
34179 SAFETY_ALLOWED_AREA_DATA::default(),
34180 )),
34181 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => Some(Self::GIMBAL_DEVICE_ATTITUDE_STATUS(
34182 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::default(),
34183 )),
34184 GLOBAL_POSITION_INT_DATA::ID => Some(Self::GLOBAL_POSITION_INT(
34185 GLOBAL_POSITION_INT_DATA::default(),
34186 )),
34187 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
34188 Some(Self::GLOBAL_VISION_POSITION_ESTIMATE(
34189 GLOBAL_VISION_POSITION_ESTIMATE_DATA::default(),
34190 ))
34191 }
34192 TUNNEL_DATA::ID => Some(Self::TUNNEL(TUNNEL_DATA::default())),
34193 PARAM_EXT_VALUE_DATA::ID => {
34194 Some(Self::PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA::default()))
34195 }
34196 TERRAIN_CHECK_DATA::ID => Some(Self::TERRAIN_CHECK(TERRAIN_CHECK_DATA::default())),
34197 COMMAND_ACK_DATA::ID => Some(Self::COMMAND_ACK(COMMAND_ACK_DATA::default())),
34198 MISSION_ITEM_DATA::ID => Some(Self::MISSION_ITEM(MISSION_ITEM_DATA::default())),
34199 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
34200 Some(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(
34201 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::default(),
34202 ))
34203 }
34204 DEBUG_DATA::ID => Some(Self::DEBUG(DEBUG_DATA::default())),
34205 GPS2_RAW_DATA::ID => Some(Self::GPS2_RAW(GPS2_RAW_DATA::default())),
34206 ONBOARD_COMPUTER_STATUS_DATA::ID => Some(Self::ONBOARD_COMPUTER_STATUS(
34207 ONBOARD_COMPUTER_STATUS_DATA::default(),
34208 )),
34209 ATTITUDE_TARGET_DATA::ID => {
34210 Some(Self::ATTITUDE_TARGET(ATTITUDE_TARGET_DATA::default()))
34211 }
34212 RC_CHANNELS_RAW_DATA::ID => {
34213 Some(Self::RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA::default()))
34214 }
34215 ODOMETRY_DATA::ID => Some(Self::ODOMETRY(ODOMETRY_DATA::default())),
34216 VISION_SPEED_ESTIMATE_DATA::ID => Some(Self::VISION_SPEED_ESTIMATE(
34217 VISION_SPEED_ESTIMATE_DATA::default(),
34218 )),
34219 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
34220 Some(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(
34221 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::default(),
34222 ))
34223 }
34224 ALTITUDE_DATA::ID => Some(Self::ALTITUDE(ALTITUDE_DATA::default())),
34225 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => Some(Self::OPEN_DRONE_ID_AUTHENTICATION(
34226 OPEN_DRONE_ID_AUTHENTICATION_DATA::default(),
34227 )),
34228 PARAM_REQUEST_LIST_DATA::ID => {
34229 Some(Self::PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA::default()))
34230 }
34231 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
34232 Some(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(
34233 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::default(),
34234 ))
34235 }
34236 _ => None,
34237 }
34238 }
34239 #[cfg(feature = "arbitrary")]
34240 fn random_message_from_id<R: rand::RngCore>(id: u32, rng: &mut R) -> Option<Self> {
34241 match id {
34242 ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::ACTUATOR_CONTROL_TARGET(
34243 ACTUATOR_CONTROL_TARGET_DATA::random(rng),
34244 )),
34245 LOG_ERASE_DATA::ID => Some(Self::LOG_ERASE(LOG_ERASE_DATA::random(rng))),
34246 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_IMAGE_STATUS(
34247 CAMERA_TRACKING_IMAGE_STATUS_DATA::random(rng),
34248 )),
34249 MISSION_WRITE_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_WRITE_PARTIAL_LIST(
34250 MISSION_WRITE_PARTIAL_LIST_DATA::random(rng),
34251 )),
34252 SCALED_PRESSURE_DATA::ID => {
34253 Some(Self::SCALED_PRESSURE(SCALED_PRESSURE_DATA::random(rng)))
34254 }
34255 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
34256 Some(Self::TRAJECTORY_REPRESENTATION_BEZIER(
34257 TRAJECTORY_REPRESENTATION_BEZIER_DATA::random(rng),
34258 ))
34259 }
34260 ORBIT_EXECUTION_STATUS_DATA::ID => Some(Self::ORBIT_EXECUTION_STATUS(
34261 ORBIT_EXECUTION_STATUS_DATA::random(rng),
34262 )),
34263 AUTH_KEY_DATA::ID => Some(Self::AUTH_KEY(AUTH_KEY_DATA::random(rng))),
34264 FILE_TRANSFER_PROTOCOL_DATA::ID => Some(Self::FILE_TRANSFER_PROTOCOL(
34265 FILE_TRANSFER_PROTOCOL_DATA::random(rng),
34266 )),
34267 SYS_STATUS_DATA::ID => Some(Self::SYS_STATUS(SYS_STATUS_DATA::random(rng))),
34268 LOG_REQUEST_END_DATA::ID => {
34269 Some(Self::LOG_REQUEST_END(LOG_REQUEST_END_DATA::random(rng)))
34270 }
34271 TERRAIN_DATA_DATA::ID => Some(Self::TERRAIN_DATA(TERRAIN_DATA_DATA::random(rng))),
34272 LOGGING_DATA_ACKED_DATA::ID => Some(Self::LOGGING_DATA_ACKED(
34273 LOGGING_DATA_ACKED_DATA::random(rng),
34274 )),
34275 NAMED_VALUE_FLOAT_DATA::ID => {
34276 Some(Self::NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA::random(rng)))
34277 }
34278 LANDING_TARGET_DATA::ID => Some(Self::LANDING_TARGET(LANDING_TARGET_DATA::random(rng))),
34279 ATT_POS_MOCAP_DATA::ID => Some(Self::ATT_POS_MOCAP(ATT_POS_MOCAP_DATA::random(rng))),
34280 SCALED_IMU3_DATA::ID => Some(Self::SCALED_IMU3(SCALED_IMU3_DATA::random(rng))),
34281 MEMORY_VECT_DATA::ID => Some(Self::MEMORY_VECT(MEMORY_VECT_DATA::random(rng))),
34282 TERRAIN_REQUEST_DATA::ID => {
34283 Some(Self::TERRAIN_REQUEST(TERRAIN_REQUEST_DATA::random(rng)))
34284 }
34285 V2_EXTENSION_DATA::ID => Some(Self::V2_EXTENSION(V2_EXTENSION_DATA::random(rng))),
34286 DEBUG_VECT_DATA::ID => Some(Self::DEBUG_VECT(DEBUG_VECT_DATA::random(rng))),
34287 MANUAL_CONTROL_DATA::ID => Some(Self::MANUAL_CONTROL(MANUAL_CONTROL_DATA::random(rng))),
34288 AIS_VESSEL_DATA::ID => Some(Self::AIS_VESSEL(AIS_VESSEL_DATA::random(rng))),
34289 UAVCAN_NODE_INFO_DATA::ID => {
34290 Some(Self::UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA::random(rng)))
34291 }
34292 SET_GPS_GLOBAL_ORIGIN_DATA::ID => Some(Self::SET_GPS_GLOBAL_ORIGIN(
34293 SET_GPS_GLOBAL_ORIGIN_DATA::random(rng),
34294 )),
34295 SCALED_PRESSURE2_DATA::ID => {
34296 Some(Self::SCALED_PRESSURE2(SCALED_PRESSURE2_DATA::random(rng)))
34297 }
34298 CAMERA_CAPTURE_STATUS_DATA::ID => Some(Self::CAMERA_CAPTURE_STATUS(
34299 CAMERA_CAPTURE_STATUS_DATA::random(rng),
34300 )),
34301 WIFI_CONFIG_AP_DATA::ID => Some(Self::WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA::random(rng))),
34302 MISSION_REQUEST_LIST_DATA::ID => Some(Self::MISSION_REQUEST_LIST(
34303 MISSION_REQUEST_LIST_DATA::random(rng),
34304 )),
34305 MISSION_ACK_DATA::ID => Some(Self::MISSION_ACK(MISSION_ACK_DATA::random(rng))),
34306 ENCAPSULATED_DATA_DATA::ID => {
34307 Some(Self::ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA::random(rng)))
34308 }
34309 UAVIONIX_ADSB_OUT_CFG_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CFG(
34310 UAVIONIX_ADSB_OUT_CFG_DATA::random(rng),
34311 )),
34312 EFI_STATUS_DATA::ID => Some(Self::EFI_STATUS(EFI_STATUS_DATA::random(rng))),
34313 OPEN_DRONE_ID_LOCATION_DATA::ID => Some(Self::OPEN_DRONE_ID_LOCATION(
34314 OPEN_DRONE_ID_LOCATION_DATA::random(rng),
34315 )),
34316 CAMERA_THERMAL_RANGE_DATA::ID => Some(Self::CAMERA_THERMAL_RANGE(
34317 CAMERA_THERMAL_RANGE_DATA::random(rng),
34318 )),
34319 LOGGING_ACK_DATA::ID => Some(Self::LOGGING_ACK(LOGGING_ACK_DATA::random(rng))),
34320 HIL_CONTROLS_DATA::ID => Some(Self::HIL_CONTROLS(HIL_CONTROLS_DATA::random(rng))),
34321 GENERATOR_STATUS_DATA::ID => {
34322 Some(Self::GENERATOR_STATUS(GENERATOR_STATUS_DATA::random(rng)))
34323 }
34324 FOLLOW_TARGET_DATA::ID => Some(Self::FOLLOW_TARGET(FOLLOW_TARGET_DATA::random(rng))),
34325 VICON_POSITION_ESTIMATE_DATA::ID => Some(Self::VICON_POSITION_ESTIMATE(
34326 VICON_POSITION_ESTIMATE_DATA::random(rng),
34327 )),
34328 ADSB_VEHICLE_DATA::ID => Some(Self::ADSB_VEHICLE(ADSB_VEHICLE_DATA::random(rng))),
34329 GIMBAL_DEVICE_INFORMATION_DATA::ID => Some(Self::GIMBAL_DEVICE_INFORMATION(
34330 GIMBAL_DEVICE_INFORMATION_DATA::random(rng),
34331 )),
34332 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID => {
34333 Some(Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(
34334 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::random(rng),
34335 ))
34336 }
34337 SMART_BATTERY_INFO_DATA::ID => Some(Self::SMART_BATTERY_INFO(
34338 SMART_BATTERY_INFO_DATA::random(rng),
34339 )),
34340 ESC_STATUS_DATA::ID => Some(Self::ESC_STATUS(ESC_STATUS_DATA::random(rng))),
34341 COLLISION_DATA::ID => Some(Self::COLLISION(COLLISION_DATA::random(rng))),
34342 LOGGING_DATA_DATA::ID => Some(Self::LOGGING_DATA(LOGGING_DATA_DATA::random(rng))),
34343 GPS_INPUT_DATA::ID => Some(Self::GPS_INPUT(GPS_INPUT_DATA::random(rng))),
34344 HOME_POSITION_DATA::ID => Some(Self::HOME_POSITION(HOME_POSITION_DATA::random(rng))),
34345 PARAM_EXT_REQUEST_READ_DATA::ID => Some(Self::PARAM_EXT_REQUEST_READ(
34346 PARAM_EXT_REQUEST_READ_DATA::random(rng),
34347 )),
34348 LOG_REQUEST_LIST_DATA::ID => {
34349 Some(Self::LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA::random(rng)))
34350 }
34351 ACTUATOR_OUTPUT_STATUS_DATA::ID => Some(Self::ACTUATOR_OUTPUT_STATUS(
34352 ACTUATOR_OUTPUT_STATUS_DATA::random(rng),
34353 )),
34354 OBSTACLE_DISTANCE_DATA::ID => {
34355 Some(Self::OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA::random(rng)))
34356 }
34357 WIND_COV_DATA::ID => Some(Self::WIND_COV(WIND_COV_DATA::random(rng))),
34358 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_DYNAMIC(
34359 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::random(rng),
34360 )),
34361 UAVIONIX_ADSB_OUT_STATUS_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_STATUS(
34362 UAVIONIX_ADSB_OUT_STATUS_DATA::random(rng),
34363 )),
34364 HIGH_LATENCY2_DATA::ID => Some(Self::HIGH_LATENCY2(HIGH_LATENCY2_DATA::random(rng))),
34365 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_DEVICE_SET_ATTITUDE(
34366 GIMBAL_DEVICE_SET_ATTITUDE_DATA::random(rng),
34367 )),
34368 PARAM_EXT_ACK_DATA::ID => Some(Self::PARAM_EXT_ACK(PARAM_EXT_ACK_DATA::random(rng))),
34369 SAFETY_SET_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_SET_ALLOWED_AREA(
34370 SAFETY_SET_ALLOWED_AREA_DATA::random(rng),
34371 )),
34372 FENCE_STATUS_DATA::ID => Some(Self::FENCE_STATUS(FENCE_STATUS_DATA::random(rng))),
34373 WINCH_STATUS_DATA::ID => Some(Self::WINCH_STATUS(WINCH_STATUS_DATA::random(rng))),
34374 ESC_INFO_DATA::ID => Some(Self::ESC_INFO(ESC_INFO_DATA::random(rng))),
34375 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_REQUEST_PARTIAL_LIST(
34376 MISSION_REQUEST_PARTIAL_LIST_DATA::random(rng),
34377 )),
34378 NAV_CONTROLLER_OUTPUT_DATA::ID => Some(Self::NAV_CONTROLLER_OUTPUT(
34379 NAV_CONTROLLER_OUTPUT_DATA::random(rng),
34380 )),
34381 HIL_OPTICAL_FLOW_DATA::ID => {
34382 Some(Self::HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA::random(rng)))
34383 }
34384 LOG_DATA_DATA::ID => Some(Self::LOG_DATA(LOG_DATA_DATA::random(rng))),
34385 HIL_STATE_QUATERNION_DATA::ID => Some(Self::HIL_STATE_QUATERNION(
34386 HIL_STATE_QUATERNION_DATA::random(rng),
34387 )),
34388 CURRENT_MODE_DATA::ID => Some(Self::CURRENT_MODE(CURRENT_MODE_DATA::random(rng))),
34389 WHEEL_DISTANCE_DATA::ID => Some(Self::WHEEL_DISTANCE(WHEEL_DISTANCE_DATA::random(rng))),
34390 OPTICAL_FLOW_DATA::ID => Some(Self::OPTICAL_FLOW(OPTICAL_FLOW_DATA::random(rng))),
34391 CHANGE_OPERATOR_CONTROL_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL(
34392 CHANGE_OPERATOR_CONTROL_DATA::random(rng),
34393 )),
34394 VIBRATION_DATA::ID => Some(Self::VIBRATION(VIBRATION_DATA::random(rng))),
34395 CAMERA_FOV_STATUS_DATA::ID => {
34396 Some(Self::CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA::random(rng)))
34397 }
34398 MISSION_COUNT_DATA::ID => Some(Self::MISSION_COUNT(MISSION_COUNT_DATA::random(rng))),
34399 OPEN_DRONE_ID_SYSTEM_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM(
34400 OPEN_DRONE_ID_SYSTEM_DATA::random(rng),
34401 )),
34402 ATTITUDE_QUATERNION_COV_DATA::ID => Some(Self::ATTITUDE_QUATERNION_COV(
34403 ATTITUDE_QUATERNION_COV_DATA::random(rng),
34404 )),
34405 POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::POSITION_TARGET_GLOBAL_INT(
34406 POSITION_TARGET_GLOBAL_INT_DATA::random(rng),
34407 )),
34408 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::SET_ACTUATOR_CONTROL_TARGET(
34409 SET_ACTUATOR_CONTROL_TARGET_DATA::random(rng),
34410 )),
34411 CELLULAR_STATUS_DATA::ID => {
34412 Some(Self::CELLULAR_STATUS(CELLULAR_STATUS_DATA::random(rng)))
34413 }
34414 COMPONENT_INFORMATION_DATA::ID => Some(Self::COMPONENT_INFORMATION(
34415 COMPONENT_INFORMATION_DATA::random(rng),
34416 )),
34417 RADIO_STATUS_DATA::ID => Some(Self::RADIO_STATUS(RADIO_STATUS_DATA::random(rng))),
34418 TIMESYNC_DATA::ID => Some(Self::TIMESYNC(TIMESYNC_DATA::random(rng))),
34419 GIMBAL_MANAGER_STATUS_DATA::ID => Some(Self::GIMBAL_MANAGER_STATUS(
34420 GIMBAL_MANAGER_STATUS_DATA::random(rng),
34421 )),
34422 COMMAND_CANCEL_DATA::ID => Some(Self::COMMAND_CANCEL(COMMAND_CANCEL_DATA::random(rng))),
34423 HIL_ACTUATOR_CONTROLS_DATA::ID => Some(Self::HIL_ACTUATOR_CONTROLS(
34424 HIL_ACTUATOR_CONTROLS_DATA::random(rng),
34425 )),
34426 NAMED_VALUE_INT_DATA::ID => {
34427 Some(Self::NAMED_VALUE_INT(NAMED_VALUE_INT_DATA::random(rng)))
34428 }
34429 DEBUG_FLOAT_ARRAY_DATA::ID => {
34430 Some(Self::DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA::random(rng)))
34431 }
34432 OPEN_DRONE_ID_BASIC_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_BASIC_ID(
34433 OPEN_DRONE_ID_BASIC_ID_DATA::random(rng),
34434 )),
34435 COMPONENT_METADATA_DATA::ID => Some(Self::COMPONENT_METADATA(
34436 COMPONENT_METADATA_DATA::random(rng),
34437 )),
34438 LINK_NODE_STATUS_DATA::ID => {
34439 Some(Self::LINK_NODE_STATUS(LINK_NODE_STATUS_DATA::random(rng)))
34440 }
34441 LOCAL_POSITION_NED_COV_DATA::ID => Some(Self::LOCAL_POSITION_NED_COV(
34442 LOCAL_POSITION_NED_COV_DATA::random(rng),
34443 )),
34444 CANFD_FRAME_DATA::ID => Some(Self::CANFD_FRAME(CANFD_FRAME_DATA::random(rng))),
34445 OPTICAL_FLOW_RAD_DATA::ID => {
34446 Some(Self::OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA::random(rng)))
34447 }
34448 PLAY_TUNE_DATA::ID => Some(Self::PLAY_TUNE(PLAY_TUNE_DATA::random(rng))),
34449 COMPONENT_INFORMATION_BASIC_DATA::ID => Some(Self::COMPONENT_INFORMATION_BASIC(
34450 COMPONENT_INFORMATION_BASIC_DATA::random(rng),
34451 )),
34452 OPEN_DRONE_ID_SELF_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_SELF_ID(
34453 OPEN_DRONE_ID_SELF_ID_DATA::random(rng),
34454 )),
34455 HEARTBEAT_DATA::ID => Some(Self::HEARTBEAT(HEARTBEAT_DATA::random(rng))),
34456 EVENT_DATA::ID => Some(Self::EVENT(EVENT_DATA::random(rng))),
34457 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_OPERATOR_ID(
34458 OPEN_DRONE_ID_OPERATOR_ID_DATA::random(rng),
34459 )),
34460 AVAILABLE_MODES_DATA::ID => {
34461 Some(Self::AVAILABLE_MODES(AVAILABLE_MODES_DATA::random(rng)))
34462 }
34463 SET_HOME_POSITION_DATA::ID => {
34464 Some(Self::SET_HOME_POSITION(SET_HOME_POSITION_DATA::random(rng)))
34465 }
34466 FUEL_STATUS_DATA::ID => Some(Self::FUEL_STATUS(FUEL_STATUS_DATA::random(rng))),
34467 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => Some(Self::OPEN_DRONE_ID_MESSAGE_PACK(
34468 OPEN_DRONE_ID_MESSAGE_PACK_DATA::random(rng),
34469 )),
34470 COMMAND_LONG_DATA::ID => Some(Self::COMMAND_LONG(COMMAND_LONG_DATA::random(rng))),
34471 GPS_RTK_DATA::ID => Some(Self::GPS_RTK(GPS_RTK_DATA::random(rng))),
34472 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID => {
34473 Some(Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(
34474 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::random(rng),
34475 ))
34476 }
34477 CAN_FILTER_MODIFY_DATA::ID => {
34478 Some(Self::CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA::random(rng)))
34479 }
34480 EXTENDED_SYS_STATE_DATA::ID => Some(Self::EXTENDED_SYS_STATE(
34481 EXTENDED_SYS_STATE_DATA::random(rng),
34482 )),
34483 UAVIONIX_ADSB_GET_DATA::ID => {
34484 Some(Self::UAVIONIX_ADSB_GET(UAVIONIX_ADSB_GET_DATA::random(rng)))
34485 }
34486 SUPPORTED_TUNES_DATA::ID => {
34487 Some(Self::SUPPORTED_TUNES(SUPPORTED_TUNES_DATA::random(rng)))
34488 }
34489 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => Some(Self::DATA_TRANSMISSION_HANDSHAKE(
34490 DATA_TRANSMISSION_HANDSHAKE_DATA::random(rng),
34491 )),
34492 PARAM_EXT_SET_DATA::ID => Some(Self::PARAM_EXT_SET(PARAM_EXT_SET_DATA::random(rng))),
34493 CAMERA_IMAGE_CAPTURED_DATA::ID => Some(Self::CAMERA_IMAGE_CAPTURED(
34494 CAMERA_IMAGE_CAPTURED_DATA::random(rng),
34495 )),
34496 REQUEST_EVENT_DATA::ID => Some(Self::REQUEST_EVENT(REQUEST_EVENT_DATA::random(rng))),
34497 GLOBAL_POSITION_INT_COV_DATA::ID => Some(Self::GLOBAL_POSITION_INT_COV(
34498 GLOBAL_POSITION_INT_COV_DATA::random(rng),
34499 )),
34500 PARAM_VALUE_DATA::ID => Some(Self::PARAM_VALUE(PARAM_VALUE_DATA::random(rng))),
34501 MAG_CAL_REPORT_DATA::ID => Some(Self::MAG_CAL_REPORT(MAG_CAL_REPORT_DATA::random(rng))),
34502 MESSAGE_INTERVAL_DATA::ID => {
34503 Some(Self::MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA::random(rng)))
34504 }
34505 PARAM_MAP_RC_DATA::ID => Some(Self::PARAM_MAP_RC(PARAM_MAP_RC_DATA::random(rng))),
34506 STATUSTEXT_DATA::ID => Some(Self::STATUSTEXT(STATUSTEXT_DATA::random(rng))),
34507 CAMERA_TRACKING_GEO_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_GEO_STATUS(
34508 CAMERA_TRACKING_GEO_STATUS_DATA::random(rng),
34509 )),
34510 GPS_INJECT_DATA_DATA::ID => {
34511 Some(Self::GPS_INJECT_DATA(GPS_INJECT_DATA_DATA::random(rng)))
34512 }
34513 VFR_HUD_DATA::ID => Some(Self::VFR_HUD(VFR_HUD_DATA::random(rng))),
34514 MISSION_ITEM_INT_DATA::ID => {
34515 Some(Self::MISSION_ITEM_INT(MISSION_ITEM_INT_DATA::random(rng)))
34516 }
34517 ISBD_LINK_STATUS_DATA::ID => {
34518 Some(Self::ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA::random(rng)))
34519 }
34520 PLAY_TUNE_V2_DATA::ID => Some(Self::PLAY_TUNE_V2(PLAY_TUNE_V2_DATA::random(rng))),
34521 CAMERA_SETTINGS_DATA::ID => {
34522 Some(Self::CAMERA_SETTINGS(CAMERA_SETTINGS_DATA::random(rng)))
34523 }
34524 MISSION_CLEAR_ALL_DATA::ID => {
34525 Some(Self::MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA::random(rng)))
34526 }
34527 MANUAL_SETPOINT_DATA::ID => {
34528 Some(Self::MANUAL_SETPOINT(MANUAL_SETPOINT_DATA::random(rng)))
34529 }
34530 MISSION_SET_CURRENT_DATA::ID => Some(Self::MISSION_SET_CURRENT(
34531 MISSION_SET_CURRENT_DATA::random(rng),
34532 )),
34533 HIL_GPS_DATA::ID => Some(Self::HIL_GPS(HIL_GPS_DATA::random(rng))),
34534 REQUEST_DATA_STREAM_DATA::ID => Some(Self::REQUEST_DATA_STREAM(
34535 REQUEST_DATA_STREAM_DATA::random(rng),
34536 )),
34537 HIGH_LATENCY_DATA::ID => Some(Self::HIGH_LATENCY(HIGH_LATENCY_DATA::random(rng))),
34538 FLIGHT_INFORMATION_DATA::ID => Some(Self::FLIGHT_INFORMATION(
34539 FLIGHT_INFORMATION_DATA::random(rng),
34540 )),
34541 SERIAL_CONTROL_DATA::ID => Some(Self::SERIAL_CONTROL(SERIAL_CONTROL_DATA::random(rng))),
34542 COMMAND_INT_DATA::ID => Some(Self::COMMAND_INT(COMMAND_INT_DATA::random(rng))),
34543 CAMERA_INFORMATION_DATA::ID => Some(Self::CAMERA_INFORMATION(
34544 CAMERA_INFORMATION_DATA::random(rng),
34545 )),
34546 SIM_STATE_DATA::ID => Some(Self::SIM_STATE(SIM_STATE_DATA::random(rng))),
34547 GPS2_RTK_DATA::ID => Some(Self::GPS2_RTK(GPS2_RTK_DATA::random(rng))),
34548 SERVO_OUTPUT_RAW_DATA::ID => {
34549 Some(Self::SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA::random(rng)))
34550 }
34551 AUTOPILOT_VERSION_DATA::ID => {
34552 Some(Self::AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA::random(rng)))
34553 }
34554 UAVCAN_NODE_STATUS_DATA::ID => Some(Self::UAVCAN_NODE_STATUS(
34555 UAVCAN_NODE_STATUS_DATA::random(rng),
34556 )),
34557 RAW_PRESSURE_DATA::ID => Some(Self::RAW_PRESSURE(RAW_PRESSURE_DATA::random(rng))),
34558 VIDEO_STREAM_STATUS_DATA::ID => Some(Self::VIDEO_STREAM_STATUS(
34559 VIDEO_STREAM_STATUS_DATA::random(rng),
34560 )),
34561 BUTTON_CHANGE_DATA::ID => Some(Self::BUTTON_CHANGE(BUTTON_CHANGE_DATA::random(rng))),
34562 PROTOCOL_VERSION_DATA::ID => {
34563 Some(Self::PROTOCOL_VERSION(PROTOCOL_VERSION_DATA::random(rng)))
34564 }
34565 DISTANCE_SENSOR_DATA::ID => {
34566 Some(Self::DISTANCE_SENSOR(DISTANCE_SENSOR_DATA::random(rng)))
34567 }
34568 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_ATTITUDE(
34569 GIMBAL_MANAGER_SET_ATTITUDE_DATA::random(rng),
34570 )),
34571 RC_CHANNELS_DATA::ID => Some(Self::RC_CHANNELS(RC_CHANNELS_DATA::random(rng))),
34572 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM_UPDATE(
34573 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::random(rng),
34574 )),
34575 ATTITUDE_QUATERNION_DATA::ID => Some(Self::ATTITUDE_QUATERNION(
34576 ATTITUDE_QUATERNION_DATA::random(rng),
34577 )),
34578 PARAM_REQUEST_READ_DATA::ID => Some(Self::PARAM_REQUEST_READ(
34579 PARAM_REQUEST_READ_DATA::random(rng),
34580 )),
34581 SCALED_PRESSURE3_DATA::ID => {
34582 Some(Self::SCALED_PRESSURE3(SCALED_PRESSURE3_DATA::random(rng)))
34583 }
34584 GIMBAL_MANAGER_INFORMATION_DATA::ID => Some(Self::GIMBAL_MANAGER_INFORMATION(
34585 GIMBAL_MANAGER_INFORMATION_DATA::random(rng),
34586 )),
34587 SETUP_SIGNING_DATA::ID => Some(Self::SETUP_SIGNING(SETUP_SIGNING_DATA::random(rng))),
34588 LOG_REQUEST_DATA_DATA::ID => {
34589 Some(Self::LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA::random(rng)))
34590 }
34591 UAVIONIX_ADSB_OUT_CONTROL_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CONTROL(
34592 UAVIONIX_ADSB_OUT_CONTROL_DATA::random(rng),
34593 )),
34594 MISSION_ITEM_REACHED_DATA::ID => Some(Self::MISSION_ITEM_REACHED(
34595 MISSION_ITEM_REACHED_DATA::random(rng),
34596 )),
34597 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::SET_POSITION_TARGET_GLOBAL_INT(
34598 SET_POSITION_TARGET_GLOBAL_INT_DATA::random(rng),
34599 )),
34600 RESPONSE_EVENT_ERROR_DATA::ID => Some(Self::RESPONSE_EVENT_ERROR(
34601 RESPONSE_EVENT_ERROR_DATA::random(rng),
34602 )),
34603 CURRENT_EVENT_SEQUENCE_DATA::ID => Some(Self::CURRENT_EVENT_SEQUENCE(
34604 CURRENT_EVENT_SEQUENCE_DATA::random(rng),
34605 )),
34606 CAN_FRAME_DATA::ID => Some(Self::CAN_FRAME(CAN_FRAME_DATA::random(rng))),
34607 MOUNT_ORIENTATION_DATA::ID => {
34608 Some(Self::MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA::random(rng)))
34609 }
34610 ILLUMINATOR_STATUS_DATA::ID => Some(Self::ILLUMINATOR_STATUS(
34611 ILLUMINATOR_STATUS_DATA::random(rng),
34612 )),
34613 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL_ACK(
34614 CHANGE_OPERATOR_CONTROL_ACK_DATA::random(rng),
34615 )),
34616 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_PITCHYAW(
34617 GIMBAL_MANAGER_SET_PITCHYAW_DATA::random(rng),
34618 )),
34619 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => Some(Self::OPEN_DRONE_ID_ARM_STATUS(
34620 OPEN_DRONE_ID_ARM_STATUS_DATA::random(rng),
34621 )),
34622 UTM_GLOBAL_POSITION_DATA::ID => Some(Self::UTM_GLOBAL_POSITION(
34623 UTM_GLOBAL_POSITION_DATA::random(rng),
34624 )),
34625 RC_CHANNELS_OVERRIDE_DATA::ID => Some(Self::RC_CHANNELS_OVERRIDE(
34626 RC_CHANNELS_OVERRIDE_DATA::random(rng),
34627 )),
34628 SCALED_IMU_DATA::ID => Some(Self::SCALED_IMU(SCALED_IMU_DATA::random(rng))),
34629 DATA_STREAM_DATA::ID => Some(Self::DATA_STREAM(DATA_STREAM_DATA::random(rng))),
34630 LOG_ENTRY_DATA::ID => Some(Self::LOG_ENTRY(LOG_ENTRY_DATA::random(rng))),
34631 PING_DATA::ID => Some(Self::PING(PING_DATA::random(rng))),
34632 POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::POSITION_TARGET_LOCAL_NED(
34633 POSITION_TARGET_LOCAL_NED_DATA::random(rng),
34634 )),
34635 SCALED_IMU2_DATA::ID => Some(Self::SCALED_IMU2(SCALED_IMU2_DATA::random(rng))),
34636 GPS_RTCM_DATA_DATA::ID => Some(Self::GPS_RTCM_DATA(GPS_RTCM_DATA_DATA::random(rng))),
34637 SET_MODE_DATA::ID => Some(Self::SET_MODE(SET_MODE_DATA::random(rng))),
34638 ESTIMATOR_STATUS_DATA::ID => {
34639 Some(Self::ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA::random(rng)))
34640 }
34641 HIL_STATE_DATA::ID => Some(Self::HIL_STATE(HIL_STATE_DATA::random(rng))),
34642 SYSTEM_TIME_DATA::ID => Some(Self::SYSTEM_TIME(SYSTEM_TIME_DATA::random(rng))),
34643 STORAGE_INFORMATION_DATA::ID => Some(Self::STORAGE_INFORMATION(
34644 STORAGE_INFORMATION_DATA::random(rng),
34645 )),
34646 BATTERY_INFO_DATA::ID => Some(Self::BATTERY_INFO(BATTERY_INFO_DATA::random(rng))),
34647 SET_ATTITUDE_TARGET_DATA::ID => Some(Self::SET_ATTITUDE_TARGET(
34648 SET_ATTITUDE_TARGET_DATA::random(rng),
34649 )),
34650 HIL_RC_INPUTS_RAW_DATA::ID => {
34651 Some(Self::HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA::random(rng)))
34652 }
34653 CAMERA_TRIGGER_DATA::ID => Some(Self::CAMERA_TRIGGER(CAMERA_TRIGGER_DATA::random(rng))),
34654 TIME_ESTIMATE_TO_TARGET_DATA::ID => Some(Self::TIME_ESTIMATE_TO_TARGET(
34655 TIME_ESTIMATE_TO_TARGET_DATA::random(rng),
34656 )),
34657 HIL_SENSOR_DATA::ID => Some(Self::HIL_SENSOR(HIL_SENSOR_DATA::random(rng))),
34658 MISSION_REQUEST_INT_DATA::ID => Some(Self::MISSION_REQUEST_INT(
34659 MISSION_REQUEST_INT_DATA::random(rng),
34660 )),
34661 TERRAIN_REPORT_DATA::ID => Some(Self::TERRAIN_REPORT(TERRAIN_REPORT_DATA::random(rng))),
34662 BATTERY_STATUS_DATA::ID => Some(Self::BATTERY_STATUS(BATTERY_STATUS_DATA::random(rng))),
34663 GPS_RAW_INT_DATA::ID => Some(Self::GPS_RAW_INT(GPS_RAW_INT_DATA::random(rng))),
34664 VISION_POSITION_ESTIMATE_DATA::ID => Some(Self::VISION_POSITION_ESTIMATE(
34665 VISION_POSITION_ESTIMATE_DATA::random(rng),
34666 )),
34667 CELLULAR_CONFIG_DATA::ID => {
34668 Some(Self::CELLULAR_CONFIG(CELLULAR_CONFIG_DATA::random(rng)))
34669 }
34670 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::SET_POSITION_TARGET_LOCAL_NED(
34671 SET_POSITION_TARGET_LOCAL_NED_DATA::random(rng),
34672 )),
34673 GPS_GLOBAL_ORIGIN_DATA::ID => {
34674 Some(Self::GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA::random(rng)))
34675 }
34676 RC_CHANNELS_SCALED_DATA::ID => Some(Self::RC_CHANNELS_SCALED(
34677 RC_CHANNELS_SCALED_DATA::random(rng),
34678 )),
34679 ATTITUDE_DATA::ID => Some(Self::ATTITUDE(ATTITUDE_DATA::random(rng))),
34680 GPS_STATUS_DATA::ID => Some(Self::GPS_STATUS(GPS_STATUS_DATA::random(rng))),
34681 CONTROL_SYSTEM_STATE_DATA::ID => Some(Self::CONTROL_SYSTEM_STATE(
34682 CONTROL_SYSTEM_STATE_DATA::random(rng),
34683 )),
34684 PARAM_EXT_REQUEST_LIST_DATA::ID => Some(Self::PARAM_EXT_REQUEST_LIST(
34685 PARAM_EXT_REQUEST_LIST_DATA::random(rng),
34686 )),
34687 VIDEO_STREAM_INFORMATION_DATA::ID => Some(Self::VIDEO_STREAM_INFORMATION(
34688 VIDEO_STREAM_INFORMATION_DATA::random(rng),
34689 )),
34690 RESOURCE_REQUEST_DATA::ID => {
34691 Some(Self::RESOURCE_REQUEST(RESOURCE_REQUEST_DATA::random(rng)))
34692 }
34693 HIGHRES_IMU_DATA::ID => Some(Self::HIGHRES_IMU(HIGHRES_IMU_DATA::random(rng))),
34694 HYGROMETER_SENSOR_DATA::ID => {
34695 Some(Self::HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA::random(rng)))
34696 }
34697 MISSION_CURRENT_DATA::ID => {
34698 Some(Self::MISSION_CURRENT(MISSION_CURRENT_DATA::random(rng)))
34699 }
34700 AVAILABLE_MODES_MONITOR_DATA::ID => Some(Self::AVAILABLE_MODES_MONITOR(
34701 AVAILABLE_MODES_MONITOR_DATA::random(rng),
34702 )),
34703 POWER_STATUS_DATA::ID => Some(Self::POWER_STATUS(POWER_STATUS_DATA::random(rng))),
34704 RAW_RPM_DATA::ID => Some(Self::RAW_RPM(RAW_RPM_DATA::random(rng))),
34705 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
34706 Some(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(
34707 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::random(rng),
34708 ))
34709 }
34710 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(
34711 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::random(rng),
34712 )),
34713 LOCAL_POSITION_NED_DATA::ID => Some(Self::LOCAL_POSITION_NED(
34714 LOCAL_POSITION_NED_DATA::random(rng),
34715 )),
34716 RAW_IMU_DATA::ID => Some(Self::RAW_IMU(RAW_IMU_DATA::random(rng))),
34717 PARAM_SET_DATA::ID => Some(Self::PARAM_SET(PARAM_SET_DATA::random(rng))),
34718 MISSION_REQUEST_DATA::ID => {
34719 Some(Self::MISSION_REQUEST(MISSION_REQUEST_DATA::random(rng)))
34720 }
34721 SAFETY_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_ALLOWED_AREA(
34722 SAFETY_ALLOWED_AREA_DATA::random(rng),
34723 )),
34724 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => Some(Self::GIMBAL_DEVICE_ATTITUDE_STATUS(
34725 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::random(rng),
34726 )),
34727 GLOBAL_POSITION_INT_DATA::ID => Some(Self::GLOBAL_POSITION_INT(
34728 GLOBAL_POSITION_INT_DATA::random(rng),
34729 )),
34730 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
34731 Some(Self::GLOBAL_VISION_POSITION_ESTIMATE(
34732 GLOBAL_VISION_POSITION_ESTIMATE_DATA::random(rng),
34733 ))
34734 }
34735 TUNNEL_DATA::ID => Some(Self::TUNNEL(TUNNEL_DATA::random(rng))),
34736 PARAM_EXT_VALUE_DATA::ID => {
34737 Some(Self::PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA::random(rng)))
34738 }
34739 TERRAIN_CHECK_DATA::ID => Some(Self::TERRAIN_CHECK(TERRAIN_CHECK_DATA::random(rng))),
34740 COMMAND_ACK_DATA::ID => Some(Self::COMMAND_ACK(COMMAND_ACK_DATA::random(rng))),
34741 MISSION_ITEM_DATA::ID => Some(Self::MISSION_ITEM(MISSION_ITEM_DATA::random(rng))),
34742 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
34743 Some(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(
34744 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::random(rng),
34745 ))
34746 }
34747 DEBUG_DATA::ID => Some(Self::DEBUG(DEBUG_DATA::random(rng))),
34748 GPS2_RAW_DATA::ID => Some(Self::GPS2_RAW(GPS2_RAW_DATA::random(rng))),
34749 ONBOARD_COMPUTER_STATUS_DATA::ID => Some(Self::ONBOARD_COMPUTER_STATUS(
34750 ONBOARD_COMPUTER_STATUS_DATA::random(rng),
34751 )),
34752 ATTITUDE_TARGET_DATA::ID => {
34753 Some(Self::ATTITUDE_TARGET(ATTITUDE_TARGET_DATA::random(rng)))
34754 }
34755 RC_CHANNELS_RAW_DATA::ID => {
34756 Some(Self::RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA::random(rng)))
34757 }
34758 ODOMETRY_DATA::ID => Some(Self::ODOMETRY(ODOMETRY_DATA::random(rng))),
34759 VISION_SPEED_ESTIMATE_DATA::ID => Some(Self::VISION_SPEED_ESTIMATE(
34760 VISION_SPEED_ESTIMATE_DATA::random(rng),
34761 )),
34762 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
34763 Some(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(
34764 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::random(rng),
34765 ))
34766 }
34767 ALTITUDE_DATA::ID => Some(Self::ALTITUDE(ALTITUDE_DATA::random(rng))),
34768 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => Some(Self::OPEN_DRONE_ID_AUTHENTICATION(
34769 OPEN_DRONE_ID_AUTHENTICATION_DATA::random(rng),
34770 )),
34771 PARAM_REQUEST_LIST_DATA::ID => Some(Self::PARAM_REQUEST_LIST(
34772 PARAM_REQUEST_LIST_DATA::random(rng),
34773 )),
34774 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
34775 Some(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(
34776 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::random(rng),
34777 ))
34778 }
34779 _ => None,
34780 }
34781 }
34782 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
34783 match self {
34784 Self::ACTUATOR_CONTROL_TARGET(body) => body.ser(version, bytes),
34785 Self::LOG_ERASE(body) => body.ser(version, bytes),
34786 Self::CAMERA_TRACKING_IMAGE_STATUS(body) => body.ser(version, bytes),
34787 Self::MISSION_WRITE_PARTIAL_LIST(body) => body.ser(version, bytes),
34788 Self::SCALED_PRESSURE(body) => body.ser(version, bytes),
34789 Self::TRAJECTORY_REPRESENTATION_BEZIER(body) => body.ser(version, bytes),
34790 Self::ORBIT_EXECUTION_STATUS(body) => body.ser(version, bytes),
34791 Self::AUTH_KEY(body) => body.ser(version, bytes),
34792 Self::FILE_TRANSFER_PROTOCOL(body) => body.ser(version, bytes),
34793 Self::SYS_STATUS(body) => body.ser(version, bytes),
34794 Self::LOG_REQUEST_END(body) => body.ser(version, bytes),
34795 Self::TERRAIN_DATA(body) => body.ser(version, bytes),
34796 Self::LOGGING_DATA_ACKED(body) => body.ser(version, bytes),
34797 Self::NAMED_VALUE_FLOAT(body) => body.ser(version, bytes),
34798 Self::LANDING_TARGET(body) => body.ser(version, bytes),
34799 Self::ATT_POS_MOCAP(body) => body.ser(version, bytes),
34800 Self::SCALED_IMU3(body) => body.ser(version, bytes),
34801 Self::MEMORY_VECT(body) => body.ser(version, bytes),
34802 Self::TERRAIN_REQUEST(body) => body.ser(version, bytes),
34803 Self::V2_EXTENSION(body) => body.ser(version, bytes),
34804 Self::DEBUG_VECT(body) => body.ser(version, bytes),
34805 Self::MANUAL_CONTROL(body) => body.ser(version, bytes),
34806 Self::AIS_VESSEL(body) => body.ser(version, bytes),
34807 Self::UAVCAN_NODE_INFO(body) => body.ser(version, bytes),
34808 Self::SET_GPS_GLOBAL_ORIGIN(body) => body.ser(version, bytes),
34809 Self::SCALED_PRESSURE2(body) => body.ser(version, bytes),
34810 Self::CAMERA_CAPTURE_STATUS(body) => body.ser(version, bytes),
34811 Self::WIFI_CONFIG_AP(body) => body.ser(version, bytes),
34812 Self::MISSION_REQUEST_LIST(body) => body.ser(version, bytes),
34813 Self::MISSION_ACK(body) => body.ser(version, bytes),
34814 Self::ENCAPSULATED_DATA(body) => body.ser(version, bytes),
34815 Self::UAVIONIX_ADSB_OUT_CFG(body) => body.ser(version, bytes),
34816 Self::EFI_STATUS(body) => body.ser(version, bytes),
34817 Self::OPEN_DRONE_ID_LOCATION(body) => body.ser(version, bytes),
34818 Self::CAMERA_THERMAL_RANGE(body) => body.ser(version, bytes),
34819 Self::LOGGING_ACK(body) => body.ser(version, bytes),
34820 Self::HIL_CONTROLS(body) => body.ser(version, bytes),
34821 Self::GENERATOR_STATUS(body) => body.ser(version, bytes),
34822 Self::FOLLOW_TARGET(body) => body.ser(version, bytes),
34823 Self::VICON_POSITION_ESTIMATE(body) => body.ser(version, bytes),
34824 Self::ADSB_VEHICLE(body) => body.ser(version, bytes),
34825 Self::GIMBAL_DEVICE_INFORMATION(body) => body.ser(version, bytes),
34826 Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(body) => body.ser(version, bytes),
34827 Self::SMART_BATTERY_INFO(body) => body.ser(version, bytes),
34828 Self::ESC_STATUS(body) => body.ser(version, bytes),
34829 Self::COLLISION(body) => body.ser(version, bytes),
34830 Self::LOGGING_DATA(body) => body.ser(version, bytes),
34831 Self::GPS_INPUT(body) => body.ser(version, bytes),
34832 Self::HOME_POSITION(body) => body.ser(version, bytes),
34833 Self::PARAM_EXT_REQUEST_READ(body) => body.ser(version, bytes),
34834 Self::LOG_REQUEST_LIST(body) => body.ser(version, bytes),
34835 Self::ACTUATOR_OUTPUT_STATUS(body) => body.ser(version, bytes),
34836 Self::OBSTACLE_DISTANCE(body) => body.ser(version, bytes),
34837 Self::WIND_COV(body) => body.ser(version, bytes),
34838 Self::UAVIONIX_ADSB_OUT_DYNAMIC(body) => body.ser(version, bytes),
34839 Self::UAVIONIX_ADSB_OUT_STATUS(body) => body.ser(version, bytes),
34840 Self::HIGH_LATENCY2(body) => body.ser(version, bytes),
34841 Self::GIMBAL_DEVICE_SET_ATTITUDE(body) => body.ser(version, bytes),
34842 Self::PARAM_EXT_ACK(body) => body.ser(version, bytes),
34843 Self::SAFETY_SET_ALLOWED_AREA(body) => body.ser(version, bytes),
34844 Self::FENCE_STATUS(body) => body.ser(version, bytes),
34845 Self::WINCH_STATUS(body) => body.ser(version, bytes),
34846 Self::ESC_INFO(body) => body.ser(version, bytes),
34847 Self::MISSION_REQUEST_PARTIAL_LIST(body) => body.ser(version, bytes),
34848 Self::NAV_CONTROLLER_OUTPUT(body) => body.ser(version, bytes),
34849 Self::HIL_OPTICAL_FLOW(body) => body.ser(version, bytes),
34850 Self::LOG_DATA(body) => body.ser(version, bytes),
34851 Self::HIL_STATE_QUATERNION(body) => body.ser(version, bytes),
34852 Self::CURRENT_MODE(body) => body.ser(version, bytes),
34853 Self::WHEEL_DISTANCE(body) => body.ser(version, bytes),
34854 Self::OPTICAL_FLOW(body) => body.ser(version, bytes),
34855 Self::CHANGE_OPERATOR_CONTROL(body) => body.ser(version, bytes),
34856 Self::VIBRATION(body) => body.ser(version, bytes),
34857 Self::CAMERA_FOV_STATUS(body) => body.ser(version, bytes),
34858 Self::MISSION_COUNT(body) => body.ser(version, bytes),
34859 Self::OPEN_DRONE_ID_SYSTEM(body) => body.ser(version, bytes),
34860 Self::ATTITUDE_QUATERNION_COV(body) => body.ser(version, bytes),
34861 Self::POSITION_TARGET_GLOBAL_INT(body) => body.ser(version, bytes),
34862 Self::SET_ACTUATOR_CONTROL_TARGET(body) => body.ser(version, bytes),
34863 Self::CELLULAR_STATUS(body) => body.ser(version, bytes),
34864 Self::COMPONENT_INFORMATION(body) => body.ser(version, bytes),
34865 Self::RADIO_STATUS(body) => body.ser(version, bytes),
34866 Self::TIMESYNC(body) => body.ser(version, bytes),
34867 Self::GIMBAL_MANAGER_STATUS(body) => body.ser(version, bytes),
34868 Self::COMMAND_CANCEL(body) => body.ser(version, bytes),
34869 Self::HIL_ACTUATOR_CONTROLS(body) => body.ser(version, bytes),
34870 Self::NAMED_VALUE_INT(body) => body.ser(version, bytes),
34871 Self::DEBUG_FLOAT_ARRAY(body) => body.ser(version, bytes),
34872 Self::OPEN_DRONE_ID_BASIC_ID(body) => body.ser(version, bytes),
34873 Self::COMPONENT_METADATA(body) => body.ser(version, bytes),
34874 Self::LINK_NODE_STATUS(body) => body.ser(version, bytes),
34875 Self::LOCAL_POSITION_NED_COV(body) => body.ser(version, bytes),
34876 Self::CANFD_FRAME(body) => body.ser(version, bytes),
34877 Self::OPTICAL_FLOW_RAD(body) => body.ser(version, bytes),
34878 Self::PLAY_TUNE(body) => body.ser(version, bytes),
34879 Self::COMPONENT_INFORMATION_BASIC(body) => body.ser(version, bytes),
34880 Self::OPEN_DRONE_ID_SELF_ID(body) => body.ser(version, bytes),
34881 Self::HEARTBEAT(body) => body.ser(version, bytes),
34882 Self::EVENT(body) => body.ser(version, bytes),
34883 Self::OPEN_DRONE_ID_OPERATOR_ID(body) => body.ser(version, bytes),
34884 Self::AVAILABLE_MODES(body) => body.ser(version, bytes),
34885 Self::SET_HOME_POSITION(body) => body.ser(version, bytes),
34886 Self::FUEL_STATUS(body) => body.ser(version, bytes),
34887 Self::OPEN_DRONE_ID_MESSAGE_PACK(body) => body.ser(version, bytes),
34888 Self::COMMAND_LONG(body) => body.ser(version, bytes),
34889 Self::GPS_RTK(body) => body.ser(version, bytes),
34890 Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(body) => body.ser(version, bytes),
34891 Self::CAN_FILTER_MODIFY(body) => body.ser(version, bytes),
34892 Self::EXTENDED_SYS_STATE(body) => body.ser(version, bytes),
34893 Self::UAVIONIX_ADSB_GET(body) => body.ser(version, bytes),
34894 Self::SUPPORTED_TUNES(body) => body.ser(version, bytes),
34895 Self::DATA_TRANSMISSION_HANDSHAKE(body) => body.ser(version, bytes),
34896 Self::PARAM_EXT_SET(body) => body.ser(version, bytes),
34897 Self::CAMERA_IMAGE_CAPTURED(body) => body.ser(version, bytes),
34898 Self::REQUEST_EVENT(body) => body.ser(version, bytes),
34899 Self::GLOBAL_POSITION_INT_COV(body) => body.ser(version, bytes),
34900 Self::PARAM_VALUE(body) => body.ser(version, bytes),
34901 Self::MAG_CAL_REPORT(body) => body.ser(version, bytes),
34902 Self::MESSAGE_INTERVAL(body) => body.ser(version, bytes),
34903 Self::PARAM_MAP_RC(body) => body.ser(version, bytes),
34904 Self::STATUSTEXT(body) => body.ser(version, bytes),
34905 Self::CAMERA_TRACKING_GEO_STATUS(body) => body.ser(version, bytes),
34906 Self::GPS_INJECT_DATA(body) => body.ser(version, bytes),
34907 Self::VFR_HUD(body) => body.ser(version, bytes),
34908 Self::MISSION_ITEM_INT(body) => body.ser(version, bytes),
34909 Self::ISBD_LINK_STATUS(body) => body.ser(version, bytes),
34910 Self::PLAY_TUNE_V2(body) => body.ser(version, bytes),
34911 Self::CAMERA_SETTINGS(body) => body.ser(version, bytes),
34912 Self::MISSION_CLEAR_ALL(body) => body.ser(version, bytes),
34913 Self::MANUAL_SETPOINT(body) => body.ser(version, bytes),
34914 Self::MISSION_SET_CURRENT(body) => body.ser(version, bytes),
34915 Self::HIL_GPS(body) => body.ser(version, bytes),
34916 Self::REQUEST_DATA_STREAM(body) => body.ser(version, bytes),
34917 Self::HIGH_LATENCY(body) => body.ser(version, bytes),
34918 Self::FLIGHT_INFORMATION(body) => body.ser(version, bytes),
34919 Self::SERIAL_CONTROL(body) => body.ser(version, bytes),
34920 Self::COMMAND_INT(body) => body.ser(version, bytes),
34921 Self::CAMERA_INFORMATION(body) => body.ser(version, bytes),
34922 Self::SIM_STATE(body) => body.ser(version, bytes),
34923 Self::GPS2_RTK(body) => body.ser(version, bytes),
34924 Self::SERVO_OUTPUT_RAW(body) => body.ser(version, bytes),
34925 Self::AUTOPILOT_VERSION(body) => body.ser(version, bytes),
34926 Self::UAVCAN_NODE_STATUS(body) => body.ser(version, bytes),
34927 Self::RAW_PRESSURE(body) => body.ser(version, bytes),
34928 Self::VIDEO_STREAM_STATUS(body) => body.ser(version, bytes),
34929 Self::BUTTON_CHANGE(body) => body.ser(version, bytes),
34930 Self::PROTOCOL_VERSION(body) => body.ser(version, bytes),
34931 Self::DISTANCE_SENSOR(body) => body.ser(version, bytes),
34932 Self::GIMBAL_MANAGER_SET_ATTITUDE(body) => body.ser(version, bytes),
34933 Self::RC_CHANNELS(body) => body.ser(version, bytes),
34934 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(body) => body.ser(version, bytes),
34935 Self::ATTITUDE_QUATERNION(body) => body.ser(version, bytes),
34936 Self::PARAM_REQUEST_READ(body) => body.ser(version, bytes),
34937 Self::SCALED_PRESSURE3(body) => body.ser(version, bytes),
34938 Self::GIMBAL_MANAGER_INFORMATION(body) => body.ser(version, bytes),
34939 Self::SETUP_SIGNING(body) => body.ser(version, bytes),
34940 Self::LOG_REQUEST_DATA(body) => body.ser(version, bytes),
34941 Self::UAVIONIX_ADSB_OUT_CONTROL(body) => body.ser(version, bytes),
34942 Self::MISSION_ITEM_REACHED(body) => body.ser(version, bytes),
34943 Self::SET_POSITION_TARGET_GLOBAL_INT(body) => body.ser(version, bytes),
34944 Self::RESPONSE_EVENT_ERROR(body) => body.ser(version, bytes),
34945 Self::CURRENT_EVENT_SEQUENCE(body) => body.ser(version, bytes),
34946 Self::CAN_FRAME(body) => body.ser(version, bytes),
34947 Self::MOUNT_ORIENTATION(body) => body.ser(version, bytes),
34948 Self::ILLUMINATOR_STATUS(body) => body.ser(version, bytes),
34949 Self::CHANGE_OPERATOR_CONTROL_ACK(body) => body.ser(version, bytes),
34950 Self::GIMBAL_MANAGER_SET_PITCHYAW(body) => body.ser(version, bytes),
34951 Self::OPEN_DRONE_ID_ARM_STATUS(body) => body.ser(version, bytes),
34952 Self::UTM_GLOBAL_POSITION(body) => body.ser(version, bytes),
34953 Self::RC_CHANNELS_OVERRIDE(body) => body.ser(version, bytes),
34954 Self::SCALED_IMU(body) => body.ser(version, bytes),
34955 Self::DATA_STREAM(body) => body.ser(version, bytes),
34956 Self::LOG_ENTRY(body) => body.ser(version, bytes),
34957 Self::PING(body) => body.ser(version, bytes),
34958 Self::POSITION_TARGET_LOCAL_NED(body) => body.ser(version, bytes),
34959 Self::SCALED_IMU2(body) => body.ser(version, bytes),
34960 Self::GPS_RTCM_DATA(body) => body.ser(version, bytes),
34961 Self::SET_MODE(body) => body.ser(version, bytes),
34962 Self::ESTIMATOR_STATUS(body) => body.ser(version, bytes),
34963 Self::HIL_STATE(body) => body.ser(version, bytes),
34964 Self::SYSTEM_TIME(body) => body.ser(version, bytes),
34965 Self::STORAGE_INFORMATION(body) => body.ser(version, bytes),
34966 Self::BATTERY_INFO(body) => body.ser(version, bytes),
34967 Self::SET_ATTITUDE_TARGET(body) => body.ser(version, bytes),
34968 Self::HIL_RC_INPUTS_RAW(body) => body.ser(version, bytes),
34969 Self::CAMERA_TRIGGER(body) => body.ser(version, bytes),
34970 Self::TIME_ESTIMATE_TO_TARGET(body) => body.ser(version, bytes),
34971 Self::HIL_SENSOR(body) => body.ser(version, bytes),
34972 Self::MISSION_REQUEST_INT(body) => body.ser(version, bytes),
34973 Self::TERRAIN_REPORT(body) => body.ser(version, bytes),
34974 Self::BATTERY_STATUS(body) => body.ser(version, bytes),
34975 Self::GPS_RAW_INT(body) => body.ser(version, bytes),
34976 Self::VISION_POSITION_ESTIMATE(body) => body.ser(version, bytes),
34977 Self::CELLULAR_CONFIG(body) => body.ser(version, bytes),
34978 Self::SET_POSITION_TARGET_LOCAL_NED(body) => body.ser(version, bytes),
34979 Self::GPS_GLOBAL_ORIGIN(body) => body.ser(version, bytes),
34980 Self::RC_CHANNELS_SCALED(body) => body.ser(version, bytes),
34981 Self::ATTITUDE(body) => body.ser(version, bytes),
34982 Self::GPS_STATUS(body) => body.ser(version, bytes),
34983 Self::CONTROL_SYSTEM_STATE(body) => body.ser(version, bytes),
34984 Self::PARAM_EXT_REQUEST_LIST(body) => body.ser(version, bytes),
34985 Self::VIDEO_STREAM_INFORMATION(body) => body.ser(version, bytes),
34986 Self::RESOURCE_REQUEST(body) => body.ser(version, bytes),
34987 Self::HIGHRES_IMU(body) => body.ser(version, bytes),
34988 Self::HYGROMETER_SENSOR(body) => body.ser(version, bytes),
34989 Self::MISSION_CURRENT(body) => body.ser(version, bytes),
34990 Self::AVAILABLE_MODES_MONITOR(body) => body.ser(version, bytes),
34991 Self::POWER_STATUS(body) => body.ser(version, bytes),
34992 Self::RAW_RPM(body) => body.ser(version, bytes),
34993 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(body) => body.ser(version, bytes),
34994 Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(body) => body.ser(version, bytes),
34995 Self::LOCAL_POSITION_NED(body) => body.ser(version, bytes),
34996 Self::RAW_IMU(body) => body.ser(version, bytes),
34997 Self::PARAM_SET(body) => body.ser(version, bytes),
34998 Self::MISSION_REQUEST(body) => body.ser(version, bytes),
34999 Self::SAFETY_ALLOWED_AREA(body) => body.ser(version, bytes),
35000 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(body) => body.ser(version, bytes),
35001 Self::GLOBAL_POSITION_INT(body) => body.ser(version, bytes),
35002 Self::GLOBAL_VISION_POSITION_ESTIMATE(body) => body.ser(version, bytes),
35003 Self::TUNNEL(body) => body.ser(version, bytes),
35004 Self::PARAM_EXT_VALUE(body) => body.ser(version, bytes),
35005 Self::TERRAIN_CHECK(body) => body.ser(version, bytes),
35006 Self::COMMAND_ACK(body) => body.ser(version, bytes),
35007 Self::MISSION_ITEM(body) => body.ser(version, bytes),
35008 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(body) => body.ser(version, bytes),
35009 Self::DEBUG(body) => body.ser(version, bytes),
35010 Self::GPS2_RAW(body) => body.ser(version, bytes),
35011 Self::ONBOARD_COMPUTER_STATUS(body) => body.ser(version, bytes),
35012 Self::ATTITUDE_TARGET(body) => body.ser(version, bytes),
35013 Self::RC_CHANNELS_RAW(body) => body.ser(version, bytes),
35014 Self::ODOMETRY(body) => body.ser(version, bytes),
35015 Self::VISION_SPEED_ESTIMATE(body) => body.ser(version, bytes),
35016 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(body) => body.ser(version, bytes),
35017 Self::ALTITUDE(body) => body.ser(version, bytes),
35018 Self::OPEN_DRONE_ID_AUTHENTICATION(body) => body.ser(version, bytes),
35019 Self::PARAM_REQUEST_LIST(body) => body.ser(version, bytes),
35020 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(body) => body.ser(version, bytes),
35021 }
35022 }
35023 fn extra_crc(id: u32) -> u8 {
35024 match id {
35025 ACTUATOR_CONTROL_TARGET_DATA::ID => ACTUATOR_CONTROL_TARGET_DATA::EXTRA_CRC,
35026 LOG_ERASE_DATA::ID => LOG_ERASE_DATA::EXTRA_CRC,
35027 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => CAMERA_TRACKING_IMAGE_STATUS_DATA::EXTRA_CRC,
35028 MISSION_WRITE_PARTIAL_LIST_DATA::ID => MISSION_WRITE_PARTIAL_LIST_DATA::EXTRA_CRC,
35029 SCALED_PRESSURE_DATA::ID => SCALED_PRESSURE_DATA::EXTRA_CRC,
35030 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
35031 TRAJECTORY_REPRESENTATION_BEZIER_DATA::EXTRA_CRC
35032 }
35033 ORBIT_EXECUTION_STATUS_DATA::ID => ORBIT_EXECUTION_STATUS_DATA::EXTRA_CRC,
35034 AUTH_KEY_DATA::ID => AUTH_KEY_DATA::EXTRA_CRC,
35035 FILE_TRANSFER_PROTOCOL_DATA::ID => FILE_TRANSFER_PROTOCOL_DATA::EXTRA_CRC,
35036 SYS_STATUS_DATA::ID => SYS_STATUS_DATA::EXTRA_CRC,
35037 LOG_REQUEST_END_DATA::ID => LOG_REQUEST_END_DATA::EXTRA_CRC,
35038 TERRAIN_DATA_DATA::ID => TERRAIN_DATA_DATA::EXTRA_CRC,
35039 LOGGING_DATA_ACKED_DATA::ID => LOGGING_DATA_ACKED_DATA::EXTRA_CRC,
35040 NAMED_VALUE_FLOAT_DATA::ID => NAMED_VALUE_FLOAT_DATA::EXTRA_CRC,
35041 LANDING_TARGET_DATA::ID => LANDING_TARGET_DATA::EXTRA_CRC,
35042 ATT_POS_MOCAP_DATA::ID => ATT_POS_MOCAP_DATA::EXTRA_CRC,
35043 SCALED_IMU3_DATA::ID => SCALED_IMU3_DATA::EXTRA_CRC,
35044 MEMORY_VECT_DATA::ID => MEMORY_VECT_DATA::EXTRA_CRC,
35045 TERRAIN_REQUEST_DATA::ID => TERRAIN_REQUEST_DATA::EXTRA_CRC,
35046 V2_EXTENSION_DATA::ID => V2_EXTENSION_DATA::EXTRA_CRC,
35047 DEBUG_VECT_DATA::ID => DEBUG_VECT_DATA::EXTRA_CRC,
35048 MANUAL_CONTROL_DATA::ID => MANUAL_CONTROL_DATA::EXTRA_CRC,
35049 AIS_VESSEL_DATA::ID => AIS_VESSEL_DATA::EXTRA_CRC,
35050 UAVCAN_NODE_INFO_DATA::ID => UAVCAN_NODE_INFO_DATA::EXTRA_CRC,
35051 SET_GPS_GLOBAL_ORIGIN_DATA::ID => SET_GPS_GLOBAL_ORIGIN_DATA::EXTRA_CRC,
35052 SCALED_PRESSURE2_DATA::ID => SCALED_PRESSURE2_DATA::EXTRA_CRC,
35053 CAMERA_CAPTURE_STATUS_DATA::ID => CAMERA_CAPTURE_STATUS_DATA::EXTRA_CRC,
35054 WIFI_CONFIG_AP_DATA::ID => WIFI_CONFIG_AP_DATA::EXTRA_CRC,
35055 MISSION_REQUEST_LIST_DATA::ID => MISSION_REQUEST_LIST_DATA::EXTRA_CRC,
35056 MISSION_ACK_DATA::ID => MISSION_ACK_DATA::EXTRA_CRC,
35057 ENCAPSULATED_DATA_DATA::ID => ENCAPSULATED_DATA_DATA::EXTRA_CRC,
35058 UAVIONIX_ADSB_OUT_CFG_DATA::ID => UAVIONIX_ADSB_OUT_CFG_DATA::EXTRA_CRC,
35059 EFI_STATUS_DATA::ID => EFI_STATUS_DATA::EXTRA_CRC,
35060 OPEN_DRONE_ID_LOCATION_DATA::ID => OPEN_DRONE_ID_LOCATION_DATA::EXTRA_CRC,
35061 CAMERA_THERMAL_RANGE_DATA::ID => CAMERA_THERMAL_RANGE_DATA::EXTRA_CRC,
35062 LOGGING_ACK_DATA::ID => LOGGING_ACK_DATA::EXTRA_CRC,
35063 HIL_CONTROLS_DATA::ID => HIL_CONTROLS_DATA::EXTRA_CRC,
35064 GENERATOR_STATUS_DATA::ID => GENERATOR_STATUS_DATA::EXTRA_CRC,
35065 FOLLOW_TARGET_DATA::ID => FOLLOW_TARGET_DATA::EXTRA_CRC,
35066 VICON_POSITION_ESTIMATE_DATA::ID => VICON_POSITION_ESTIMATE_DATA::EXTRA_CRC,
35067 ADSB_VEHICLE_DATA::ID => ADSB_VEHICLE_DATA::EXTRA_CRC,
35068 GIMBAL_DEVICE_INFORMATION_DATA::ID => GIMBAL_DEVICE_INFORMATION_DATA::EXTRA_CRC,
35069 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID => {
35070 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::EXTRA_CRC
35071 }
35072 SMART_BATTERY_INFO_DATA::ID => SMART_BATTERY_INFO_DATA::EXTRA_CRC,
35073 ESC_STATUS_DATA::ID => ESC_STATUS_DATA::EXTRA_CRC,
35074 COLLISION_DATA::ID => COLLISION_DATA::EXTRA_CRC,
35075 LOGGING_DATA_DATA::ID => LOGGING_DATA_DATA::EXTRA_CRC,
35076 GPS_INPUT_DATA::ID => GPS_INPUT_DATA::EXTRA_CRC,
35077 HOME_POSITION_DATA::ID => HOME_POSITION_DATA::EXTRA_CRC,
35078 PARAM_EXT_REQUEST_READ_DATA::ID => PARAM_EXT_REQUEST_READ_DATA::EXTRA_CRC,
35079 LOG_REQUEST_LIST_DATA::ID => LOG_REQUEST_LIST_DATA::EXTRA_CRC,
35080 ACTUATOR_OUTPUT_STATUS_DATA::ID => ACTUATOR_OUTPUT_STATUS_DATA::EXTRA_CRC,
35081 OBSTACLE_DISTANCE_DATA::ID => OBSTACLE_DISTANCE_DATA::EXTRA_CRC,
35082 WIND_COV_DATA::ID => WIND_COV_DATA::EXTRA_CRC,
35083 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID => UAVIONIX_ADSB_OUT_DYNAMIC_DATA::EXTRA_CRC,
35084 UAVIONIX_ADSB_OUT_STATUS_DATA::ID => UAVIONIX_ADSB_OUT_STATUS_DATA::EXTRA_CRC,
35085 HIGH_LATENCY2_DATA::ID => HIGH_LATENCY2_DATA::EXTRA_CRC,
35086 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => GIMBAL_DEVICE_SET_ATTITUDE_DATA::EXTRA_CRC,
35087 PARAM_EXT_ACK_DATA::ID => PARAM_EXT_ACK_DATA::EXTRA_CRC,
35088 SAFETY_SET_ALLOWED_AREA_DATA::ID => SAFETY_SET_ALLOWED_AREA_DATA::EXTRA_CRC,
35089 FENCE_STATUS_DATA::ID => FENCE_STATUS_DATA::EXTRA_CRC,
35090 WINCH_STATUS_DATA::ID => WINCH_STATUS_DATA::EXTRA_CRC,
35091 ESC_INFO_DATA::ID => ESC_INFO_DATA::EXTRA_CRC,
35092 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => MISSION_REQUEST_PARTIAL_LIST_DATA::EXTRA_CRC,
35093 NAV_CONTROLLER_OUTPUT_DATA::ID => NAV_CONTROLLER_OUTPUT_DATA::EXTRA_CRC,
35094 HIL_OPTICAL_FLOW_DATA::ID => HIL_OPTICAL_FLOW_DATA::EXTRA_CRC,
35095 LOG_DATA_DATA::ID => LOG_DATA_DATA::EXTRA_CRC,
35096 HIL_STATE_QUATERNION_DATA::ID => HIL_STATE_QUATERNION_DATA::EXTRA_CRC,
35097 CURRENT_MODE_DATA::ID => CURRENT_MODE_DATA::EXTRA_CRC,
35098 WHEEL_DISTANCE_DATA::ID => WHEEL_DISTANCE_DATA::EXTRA_CRC,
35099 OPTICAL_FLOW_DATA::ID => OPTICAL_FLOW_DATA::EXTRA_CRC,
35100 CHANGE_OPERATOR_CONTROL_DATA::ID => CHANGE_OPERATOR_CONTROL_DATA::EXTRA_CRC,
35101 VIBRATION_DATA::ID => VIBRATION_DATA::EXTRA_CRC,
35102 CAMERA_FOV_STATUS_DATA::ID => CAMERA_FOV_STATUS_DATA::EXTRA_CRC,
35103 MISSION_COUNT_DATA::ID => MISSION_COUNT_DATA::EXTRA_CRC,
35104 OPEN_DRONE_ID_SYSTEM_DATA::ID => OPEN_DRONE_ID_SYSTEM_DATA::EXTRA_CRC,
35105 ATTITUDE_QUATERNION_COV_DATA::ID => ATTITUDE_QUATERNION_COV_DATA::EXTRA_CRC,
35106 POSITION_TARGET_GLOBAL_INT_DATA::ID => POSITION_TARGET_GLOBAL_INT_DATA::EXTRA_CRC,
35107 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => SET_ACTUATOR_CONTROL_TARGET_DATA::EXTRA_CRC,
35108 CELLULAR_STATUS_DATA::ID => CELLULAR_STATUS_DATA::EXTRA_CRC,
35109 COMPONENT_INFORMATION_DATA::ID => COMPONENT_INFORMATION_DATA::EXTRA_CRC,
35110 RADIO_STATUS_DATA::ID => RADIO_STATUS_DATA::EXTRA_CRC,
35111 TIMESYNC_DATA::ID => TIMESYNC_DATA::EXTRA_CRC,
35112 GIMBAL_MANAGER_STATUS_DATA::ID => GIMBAL_MANAGER_STATUS_DATA::EXTRA_CRC,
35113 COMMAND_CANCEL_DATA::ID => COMMAND_CANCEL_DATA::EXTRA_CRC,
35114 HIL_ACTUATOR_CONTROLS_DATA::ID => HIL_ACTUATOR_CONTROLS_DATA::EXTRA_CRC,
35115 NAMED_VALUE_INT_DATA::ID => NAMED_VALUE_INT_DATA::EXTRA_CRC,
35116 DEBUG_FLOAT_ARRAY_DATA::ID => DEBUG_FLOAT_ARRAY_DATA::EXTRA_CRC,
35117 OPEN_DRONE_ID_BASIC_ID_DATA::ID => OPEN_DRONE_ID_BASIC_ID_DATA::EXTRA_CRC,
35118 COMPONENT_METADATA_DATA::ID => COMPONENT_METADATA_DATA::EXTRA_CRC,
35119 LINK_NODE_STATUS_DATA::ID => LINK_NODE_STATUS_DATA::EXTRA_CRC,
35120 LOCAL_POSITION_NED_COV_DATA::ID => LOCAL_POSITION_NED_COV_DATA::EXTRA_CRC,
35121 CANFD_FRAME_DATA::ID => CANFD_FRAME_DATA::EXTRA_CRC,
35122 OPTICAL_FLOW_RAD_DATA::ID => OPTICAL_FLOW_RAD_DATA::EXTRA_CRC,
35123 PLAY_TUNE_DATA::ID => PLAY_TUNE_DATA::EXTRA_CRC,
35124 COMPONENT_INFORMATION_BASIC_DATA::ID => COMPONENT_INFORMATION_BASIC_DATA::EXTRA_CRC,
35125 OPEN_DRONE_ID_SELF_ID_DATA::ID => OPEN_DRONE_ID_SELF_ID_DATA::EXTRA_CRC,
35126 HEARTBEAT_DATA::ID => HEARTBEAT_DATA::EXTRA_CRC,
35127 EVENT_DATA::ID => EVENT_DATA::EXTRA_CRC,
35128 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => OPEN_DRONE_ID_OPERATOR_ID_DATA::EXTRA_CRC,
35129 AVAILABLE_MODES_DATA::ID => AVAILABLE_MODES_DATA::EXTRA_CRC,
35130 SET_HOME_POSITION_DATA::ID => SET_HOME_POSITION_DATA::EXTRA_CRC,
35131 FUEL_STATUS_DATA::ID => FUEL_STATUS_DATA::EXTRA_CRC,
35132 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => OPEN_DRONE_ID_MESSAGE_PACK_DATA::EXTRA_CRC,
35133 COMMAND_LONG_DATA::ID => COMMAND_LONG_DATA::EXTRA_CRC,
35134 GPS_RTK_DATA::ID => GPS_RTK_DATA::EXTRA_CRC,
35135 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID => {
35136 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::EXTRA_CRC
35137 }
35138 CAN_FILTER_MODIFY_DATA::ID => CAN_FILTER_MODIFY_DATA::EXTRA_CRC,
35139 EXTENDED_SYS_STATE_DATA::ID => EXTENDED_SYS_STATE_DATA::EXTRA_CRC,
35140 UAVIONIX_ADSB_GET_DATA::ID => UAVIONIX_ADSB_GET_DATA::EXTRA_CRC,
35141 SUPPORTED_TUNES_DATA::ID => SUPPORTED_TUNES_DATA::EXTRA_CRC,
35142 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => DATA_TRANSMISSION_HANDSHAKE_DATA::EXTRA_CRC,
35143 PARAM_EXT_SET_DATA::ID => PARAM_EXT_SET_DATA::EXTRA_CRC,
35144 CAMERA_IMAGE_CAPTURED_DATA::ID => CAMERA_IMAGE_CAPTURED_DATA::EXTRA_CRC,
35145 REQUEST_EVENT_DATA::ID => REQUEST_EVENT_DATA::EXTRA_CRC,
35146 GLOBAL_POSITION_INT_COV_DATA::ID => GLOBAL_POSITION_INT_COV_DATA::EXTRA_CRC,
35147 PARAM_VALUE_DATA::ID => PARAM_VALUE_DATA::EXTRA_CRC,
35148 MAG_CAL_REPORT_DATA::ID => MAG_CAL_REPORT_DATA::EXTRA_CRC,
35149 MESSAGE_INTERVAL_DATA::ID => MESSAGE_INTERVAL_DATA::EXTRA_CRC,
35150 PARAM_MAP_RC_DATA::ID => PARAM_MAP_RC_DATA::EXTRA_CRC,
35151 STATUSTEXT_DATA::ID => STATUSTEXT_DATA::EXTRA_CRC,
35152 CAMERA_TRACKING_GEO_STATUS_DATA::ID => CAMERA_TRACKING_GEO_STATUS_DATA::EXTRA_CRC,
35153 GPS_INJECT_DATA_DATA::ID => GPS_INJECT_DATA_DATA::EXTRA_CRC,
35154 VFR_HUD_DATA::ID => VFR_HUD_DATA::EXTRA_CRC,
35155 MISSION_ITEM_INT_DATA::ID => MISSION_ITEM_INT_DATA::EXTRA_CRC,
35156 ISBD_LINK_STATUS_DATA::ID => ISBD_LINK_STATUS_DATA::EXTRA_CRC,
35157 PLAY_TUNE_V2_DATA::ID => PLAY_TUNE_V2_DATA::EXTRA_CRC,
35158 CAMERA_SETTINGS_DATA::ID => CAMERA_SETTINGS_DATA::EXTRA_CRC,
35159 MISSION_CLEAR_ALL_DATA::ID => MISSION_CLEAR_ALL_DATA::EXTRA_CRC,
35160 MANUAL_SETPOINT_DATA::ID => MANUAL_SETPOINT_DATA::EXTRA_CRC,
35161 MISSION_SET_CURRENT_DATA::ID => MISSION_SET_CURRENT_DATA::EXTRA_CRC,
35162 HIL_GPS_DATA::ID => HIL_GPS_DATA::EXTRA_CRC,
35163 REQUEST_DATA_STREAM_DATA::ID => REQUEST_DATA_STREAM_DATA::EXTRA_CRC,
35164 HIGH_LATENCY_DATA::ID => HIGH_LATENCY_DATA::EXTRA_CRC,
35165 FLIGHT_INFORMATION_DATA::ID => FLIGHT_INFORMATION_DATA::EXTRA_CRC,
35166 SERIAL_CONTROL_DATA::ID => SERIAL_CONTROL_DATA::EXTRA_CRC,
35167 COMMAND_INT_DATA::ID => COMMAND_INT_DATA::EXTRA_CRC,
35168 CAMERA_INFORMATION_DATA::ID => CAMERA_INFORMATION_DATA::EXTRA_CRC,
35169 SIM_STATE_DATA::ID => SIM_STATE_DATA::EXTRA_CRC,
35170 GPS2_RTK_DATA::ID => GPS2_RTK_DATA::EXTRA_CRC,
35171 SERVO_OUTPUT_RAW_DATA::ID => SERVO_OUTPUT_RAW_DATA::EXTRA_CRC,
35172 AUTOPILOT_VERSION_DATA::ID => AUTOPILOT_VERSION_DATA::EXTRA_CRC,
35173 UAVCAN_NODE_STATUS_DATA::ID => UAVCAN_NODE_STATUS_DATA::EXTRA_CRC,
35174 RAW_PRESSURE_DATA::ID => RAW_PRESSURE_DATA::EXTRA_CRC,
35175 VIDEO_STREAM_STATUS_DATA::ID => VIDEO_STREAM_STATUS_DATA::EXTRA_CRC,
35176 BUTTON_CHANGE_DATA::ID => BUTTON_CHANGE_DATA::EXTRA_CRC,
35177 PROTOCOL_VERSION_DATA::ID => PROTOCOL_VERSION_DATA::EXTRA_CRC,
35178 DISTANCE_SENSOR_DATA::ID => DISTANCE_SENSOR_DATA::EXTRA_CRC,
35179 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => GIMBAL_MANAGER_SET_ATTITUDE_DATA::EXTRA_CRC,
35180 RC_CHANNELS_DATA::ID => RC_CHANNELS_DATA::EXTRA_CRC,
35181 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::EXTRA_CRC,
35182 ATTITUDE_QUATERNION_DATA::ID => ATTITUDE_QUATERNION_DATA::EXTRA_CRC,
35183 PARAM_REQUEST_READ_DATA::ID => PARAM_REQUEST_READ_DATA::EXTRA_CRC,
35184 SCALED_PRESSURE3_DATA::ID => SCALED_PRESSURE3_DATA::EXTRA_CRC,
35185 GIMBAL_MANAGER_INFORMATION_DATA::ID => GIMBAL_MANAGER_INFORMATION_DATA::EXTRA_CRC,
35186 SETUP_SIGNING_DATA::ID => SETUP_SIGNING_DATA::EXTRA_CRC,
35187 LOG_REQUEST_DATA_DATA::ID => LOG_REQUEST_DATA_DATA::EXTRA_CRC,
35188 UAVIONIX_ADSB_OUT_CONTROL_DATA::ID => UAVIONIX_ADSB_OUT_CONTROL_DATA::EXTRA_CRC,
35189 MISSION_ITEM_REACHED_DATA::ID => MISSION_ITEM_REACHED_DATA::EXTRA_CRC,
35190 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => {
35191 SET_POSITION_TARGET_GLOBAL_INT_DATA::EXTRA_CRC
35192 }
35193 RESPONSE_EVENT_ERROR_DATA::ID => RESPONSE_EVENT_ERROR_DATA::EXTRA_CRC,
35194 CURRENT_EVENT_SEQUENCE_DATA::ID => CURRENT_EVENT_SEQUENCE_DATA::EXTRA_CRC,
35195 CAN_FRAME_DATA::ID => CAN_FRAME_DATA::EXTRA_CRC,
35196 MOUNT_ORIENTATION_DATA::ID => MOUNT_ORIENTATION_DATA::EXTRA_CRC,
35197 ILLUMINATOR_STATUS_DATA::ID => ILLUMINATOR_STATUS_DATA::EXTRA_CRC,
35198 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => CHANGE_OPERATOR_CONTROL_ACK_DATA::EXTRA_CRC,
35199 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => GIMBAL_MANAGER_SET_PITCHYAW_DATA::EXTRA_CRC,
35200 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => OPEN_DRONE_ID_ARM_STATUS_DATA::EXTRA_CRC,
35201 UTM_GLOBAL_POSITION_DATA::ID => UTM_GLOBAL_POSITION_DATA::EXTRA_CRC,
35202 RC_CHANNELS_OVERRIDE_DATA::ID => RC_CHANNELS_OVERRIDE_DATA::EXTRA_CRC,
35203 SCALED_IMU_DATA::ID => SCALED_IMU_DATA::EXTRA_CRC,
35204 DATA_STREAM_DATA::ID => DATA_STREAM_DATA::EXTRA_CRC,
35205 LOG_ENTRY_DATA::ID => LOG_ENTRY_DATA::EXTRA_CRC,
35206 PING_DATA::ID => PING_DATA::EXTRA_CRC,
35207 POSITION_TARGET_LOCAL_NED_DATA::ID => POSITION_TARGET_LOCAL_NED_DATA::EXTRA_CRC,
35208 SCALED_IMU2_DATA::ID => SCALED_IMU2_DATA::EXTRA_CRC,
35209 GPS_RTCM_DATA_DATA::ID => GPS_RTCM_DATA_DATA::EXTRA_CRC,
35210 SET_MODE_DATA::ID => SET_MODE_DATA::EXTRA_CRC,
35211 ESTIMATOR_STATUS_DATA::ID => ESTIMATOR_STATUS_DATA::EXTRA_CRC,
35212 HIL_STATE_DATA::ID => HIL_STATE_DATA::EXTRA_CRC,
35213 SYSTEM_TIME_DATA::ID => SYSTEM_TIME_DATA::EXTRA_CRC,
35214 STORAGE_INFORMATION_DATA::ID => STORAGE_INFORMATION_DATA::EXTRA_CRC,
35215 BATTERY_INFO_DATA::ID => BATTERY_INFO_DATA::EXTRA_CRC,
35216 SET_ATTITUDE_TARGET_DATA::ID => SET_ATTITUDE_TARGET_DATA::EXTRA_CRC,
35217 HIL_RC_INPUTS_RAW_DATA::ID => HIL_RC_INPUTS_RAW_DATA::EXTRA_CRC,
35218 CAMERA_TRIGGER_DATA::ID => CAMERA_TRIGGER_DATA::EXTRA_CRC,
35219 TIME_ESTIMATE_TO_TARGET_DATA::ID => TIME_ESTIMATE_TO_TARGET_DATA::EXTRA_CRC,
35220 HIL_SENSOR_DATA::ID => HIL_SENSOR_DATA::EXTRA_CRC,
35221 MISSION_REQUEST_INT_DATA::ID => MISSION_REQUEST_INT_DATA::EXTRA_CRC,
35222 TERRAIN_REPORT_DATA::ID => TERRAIN_REPORT_DATA::EXTRA_CRC,
35223 BATTERY_STATUS_DATA::ID => BATTERY_STATUS_DATA::EXTRA_CRC,
35224 GPS_RAW_INT_DATA::ID => GPS_RAW_INT_DATA::EXTRA_CRC,
35225 VISION_POSITION_ESTIMATE_DATA::ID => VISION_POSITION_ESTIMATE_DATA::EXTRA_CRC,
35226 CELLULAR_CONFIG_DATA::ID => CELLULAR_CONFIG_DATA::EXTRA_CRC,
35227 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => SET_POSITION_TARGET_LOCAL_NED_DATA::EXTRA_CRC,
35228 GPS_GLOBAL_ORIGIN_DATA::ID => GPS_GLOBAL_ORIGIN_DATA::EXTRA_CRC,
35229 RC_CHANNELS_SCALED_DATA::ID => RC_CHANNELS_SCALED_DATA::EXTRA_CRC,
35230 ATTITUDE_DATA::ID => ATTITUDE_DATA::EXTRA_CRC,
35231 GPS_STATUS_DATA::ID => GPS_STATUS_DATA::EXTRA_CRC,
35232 CONTROL_SYSTEM_STATE_DATA::ID => CONTROL_SYSTEM_STATE_DATA::EXTRA_CRC,
35233 PARAM_EXT_REQUEST_LIST_DATA::ID => PARAM_EXT_REQUEST_LIST_DATA::EXTRA_CRC,
35234 VIDEO_STREAM_INFORMATION_DATA::ID => VIDEO_STREAM_INFORMATION_DATA::EXTRA_CRC,
35235 RESOURCE_REQUEST_DATA::ID => RESOURCE_REQUEST_DATA::EXTRA_CRC,
35236 HIGHRES_IMU_DATA::ID => HIGHRES_IMU_DATA::EXTRA_CRC,
35237 HYGROMETER_SENSOR_DATA::ID => HYGROMETER_SENSOR_DATA::EXTRA_CRC,
35238 MISSION_CURRENT_DATA::ID => MISSION_CURRENT_DATA::EXTRA_CRC,
35239 AVAILABLE_MODES_MONITOR_DATA::ID => AVAILABLE_MODES_MONITOR_DATA::EXTRA_CRC,
35240 POWER_STATUS_DATA::ID => POWER_STATUS_DATA::EXTRA_CRC,
35241 RAW_RPM_DATA::ID => RAW_RPM_DATA::EXTRA_CRC,
35242 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
35243 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::EXTRA_CRC
35244 }
35245 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID => {
35246 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::EXTRA_CRC
35247 }
35248 LOCAL_POSITION_NED_DATA::ID => LOCAL_POSITION_NED_DATA::EXTRA_CRC,
35249 RAW_IMU_DATA::ID => RAW_IMU_DATA::EXTRA_CRC,
35250 PARAM_SET_DATA::ID => PARAM_SET_DATA::EXTRA_CRC,
35251 MISSION_REQUEST_DATA::ID => MISSION_REQUEST_DATA::EXTRA_CRC,
35252 SAFETY_ALLOWED_AREA_DATA::ID => SAFETY_ALLOWED_AREA_DATA::EXTRA_CRC,
35253 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::EXTRA_CRC,
35254 GLOBAL_POSITION_INT_DATA::ID => GLOBAL_POSITION_INT_DATA::EXTRA_CRC,
35255 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
35256 GLOBAL_VISION_POSITION_ESTIMATE_DATA::EXTRA_CRC
35257 }
35258 TUNNEL_DATA::ID => TUNNEL_DATA::EXTRA_CRC,
35259 PARAM_EXT_VALUE_DATA::ID => PARAM_EXT_VALUE_DATA::EXTRA_CRC,
35260 TERRAIN_CHECK_DATA::ID => TERRAIN_CHECK_DATA::EXTRA_CRC,
35261 COMMAND_ACK_DATA::ID => COMMAND_ACK_DATA::EXTRA_CRC,
35262 MISSION_ITEM_DATA::ID => MISSION_ITEM_DATA::EXTRA_CRC,
35263 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
35264 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::EXTRA_CRC
35265 }
35266 DEBUG_DATA::ID => DEBUG_DATA::EXTRA_CRC,
35267 GPS2_RAW_DATA::ID => GPS2_RAW_DATA::EXTRA_CRC,
35268 ONBOARD_COMPUTER_STATUS_DATA::ID => ONBOARD_COMPUTER_STATUS_DATA::EXTRA_CRC,
35269 ATTITUDE_TARGET_DATA::ID => ATTITUDE_TARGET_DATA::EXTRA_CRC,
35270 RC_CHANNELS_RAW_DATA::ID => RC_CHANNELS_RAW_DATA::EXTRA_CRC,
35271 ODOMETRY_DATA::ID => ODOMETRY_DATA::EXTRA_CRC,
35272 VISION_SPEED_ESTIMATE_DATA::ID => VISION_SPEED_ESTIMATE_DATA::EXTRA_CRC,
35273 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
35274 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::EXTRA_CRC
35275 }
35276 ALTITUDE_DATA::ID => ALTITUDE_DATA::EXTRA_CRC,
35277 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => OPEN_DRONE_ID_AUTHENTICATION_DATA::EXTRA_CRC,
35278 PARAM_REQUEST_LIST_DATA::ID => PARAM_REQUEST_LIST_DATA::EXTRA_CRC,
35279 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
35280 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::EXTRA_CRC
35281 }
35282 _ => 0,
35283 }
35284 }
35285 fn target_system_id(&self) -> Option<u8> {
35286 match self {
35287 Self::LOG_ERASE(inner) => Some(inner.target_system),
35288 Self::MISSION_WRITE_PARTIAL_LIST(inner) => Some(inner.target_system),
35289 Self::FILE_TRANSFER_PROTOCOL(inner) => Some(inner.target_system),
35290 Self::LOG_REQUEST_END(inner) => Some(inner.target_system),
35291 Self::LOGGING_DATA_ACKED(inner) => Some(inner.target_system),
35292 Self::V2_EXTENSION(inner) => Some(inner.target_system),
35293 Self::SET_GPS_GLOBAL_ORIGIN(inner) => Some(inner.target_system),
35294 Self::MISSION_REQUEST_LIST(inner) => Some(inner.target_system),
35295 Self::MISSION_ACK(inner) => Some(inner.target_system),
35296 Self::OPEN_DRONE_ID_LOCATION(inner) => Some(inner.target_system),
35297 Self::LOGGING_ACK(inner) => Some(inner.target_system),
35298 Self::LOGGING_DATA(inner) => Some(inner.target_system),
35299 Self::PARAM_EXT_REQUEST_READ(inner) => Some(inner.target_system),
35300 Self::LOG_REQUEST_LIST(inner) => Some(inner.target_system),
35301 Self::GIMBAL_DEVICE_SET_ATTITUDE(inner) => Some(inner.target_system),
35302 Self::SAFETY_SET_ALLOWED_AREA(inner) => Some(inner.target_system),
35303 Self::MISSION_REQUEST_PARTIAL_LIST(inner) => Some(inner.target_system),
35304 Self::CHANGE_OPERATOR_CONTROL(inner) => Some(inner.target_system),
35305 Self::MISSION_COUNT(inner) => Some(inner.target_system),
35306 Self::OPEN_DRONE_ID_SYSTEM(inner) => Some(inner.target_system),
35307 Self::SET_ACTUATOR_CONTROL_TARGET(inner) => Some(inner.target_system),
35308 Self::TIMESYNC(inner) => Some(inner.target_system),
35309 Self::COMMAND_CANCEL(inner) => Some(inner.target_system),
35310 Self::OPEN_DRONE_ID_BASIC_ID(inner) => Some(inner.target_system),
35311 Self::CANFD_FRAME(inner) => Some(inner.target_system),
35312 Self::PLAY_TUNE(inner) => Some(inner.target_system),
35313 Self::OPEN_DRONE_ID_SELF_ID(inner) => Some(inner.target_system),
35314 Self::OPEN_DRONE_ID_OPERATOR_ID(inner) => Some(inner.target_system),
35315 Self::SET_HOME_POSITION(inner) => Some(inner.target_system),
35316 Self::OPEN_DRONE_ID_MESSAGE_PACK(inner) => Some(inner.target_system),
35317 Self::COMMAND_LONG(inner) => Some(inner.target_system),
35318 Self::CAN_FILTER_MODIFY(inner) => Some(inner.target_system),
35319 Self::SUPPORTED_TUNES(inner) => Some(inner.target_system),
35320 Self::PARAM_EXT_SET(inner) => Some(inner.target_system),
35321 Self::REQUEST_EVENT(inner) => Some(inner.target_system),
35322 Self::PARAM_MAP_RC(inner) => Some(inner.target_system),
35323 Self::GPS_INJECT_DATA(inner) => Some(inner.target_system),
35324 Self::MISSION_ITEM_INT(inner) => Some(inner.target_system),
35325 Self::PLAY_TUNE_V2(inner) => Some(inner.target_system),
35326 Self::MISSION_CLEAR_ALL(inner) => Some(inner.target_system),
35327 Self::MISSION_SET_CURRENT(inner) => Some(inner.target_system),
35328 Self::REQUEST_DATA_STREAM(inner) => Some(inner.target_system),
35329 Self::SERIAL_CONTROL(inner) => Some(inner.target_system),
35330 Self::COMMAND_INT(inner) => Some(inner.target_system),
35331 Self::GIMBAL_MANAGER_SET_ATTITUDE(inner) => Some(inner.target_system),
35332 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(inner) => Some(inner.target_system),
35333 Self::PARAM_REQUEST_READ(inner) => Some(inner.target_system),
35334 Self::SETUP_SIGNING(inner) => Some(inner.target_system),
35335 Self::LOG_REQUEST_DATA(inner) => Some(inner.target_system),
35336 Self::SET_POSITION_TARGET_GLOBAL_INT(inner) => Some(inner.target_system),
35337 Self::RESPONSE_EVENT_ERROR(inner) => Some(inner.target_system),
35338 Self::CAN_FRAME(inner) => Some(inner.target_system),
35339 Self::GIMBAL_MANAGER_SET_PITCHYAW(inner) => Some(inner.target_system),
35340 Self::RC_CHANNELS_OVERRIDE(inner) => Some(inner.target_system),
35341 Self::PING(inner) => Some(inner.target_system),
35342 Self::SET_MODE(inner) => Some(inner.target_system),
35343 Self::SET_ATTITUDE_TARGET(inner) => Some(inner.target_system),
35344 Self::MISSION_REQUEST_INT(inner) => Some(inner.target_system),
35345 Self::SET_POSITION_TARGET_LOCAL_NED(inner) => Some(inner.target_system),
35346 Self::PARAM_EXT_REQUEST_LIST(inner) => Some(inner.target_system),
35347 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(inner) => Some(inner.target_system),
35348 Self::PARAM_SET(inner) => Some(inner.target_system),
35349 Self::MISSION_REQUEST(inner) => Some(inner.target_system),
35350 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(inner) => Some(inner.target_system),
35351 Self::TUNNEL(inner) => Some(inner.target_system),
35352 Self::COMMAND_ACK(inner) => Some(inner.target_system),
35353 Self::MISSION_ITEM(inner) => Some(inner.target_system),
35354 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(inner) => Some(inner.target_system),
35355 Self::OPEN_DRONE_ID_AUTHENTICATION(inner) => Some(inner.target_system),
35356 Self::PARAM_REQUEST_LIST(inner) => Some(inner.target_system),
35357 _ => None,
35358 }
35359 }
35360 fn target_component_id(&self) -> Option<u8> {
35361 match self {
35362 Self::LOG_ERASE(inner) => Some(inner.target_component),
35363 Self::MISSION_WRITE_PARTIAL_LIST(inner) => Some(inner.target_component),
35364 Self::FILE_TRANSFER_PROTOCOL(inner) => Some(inner.target_component),
35365 Self::LOG_REQUEST_END(inner) => Some(inner.target_component),
35366 Self::LOGGING_DATA_ACKED(inner) => Some(inner.target_component),
35367 Self::V2_EXTENSION(inner) => Some(inner.target_component),
35368 Self::MISSION_REQUEST_LIST(inner) => Some(inner.target_component),
35369 Self::MISSION_ACK(inner) => Some(inner.target_component),
35370 Self::OPEN_DRONE_ID_LOCATION(inner) => Some(inner.target_component),
35371 Self::LOGGING_ACK(inner) => Some(inner.target_component),
35372 Self::LOGGING_DATA(inner) => Some(inner.target_component),
35373 Self::PARAM_EXT_REQUEST_READ(inner) => Some(inner.target_component),
35374 Self::LOG_REQUEST_LIST(inner) => Some(inner.target_component),
35375 Self::GIMBAL_DEVICE_SET_ATTITUDE(inner) => Some(inner.target_component),
35376 Self::SAFETY_SET_ALLOWED_AREA(inner) => Some(inner.target_component),
35377 Self::MISSION_REQUEST_PARTIAL_LIST(inner) => Some(inner.target_component),
35378 Self::MISSION_COUNT(inner) => Some(inner.target_component),
35379 Self::OPEN_DRONE_ID_SYSTEM(inner) => Some(inner.target_component),
35380 Self::SET_ACTUATOR_CONTROL_TARGET(inner) => Some(inner.target_component),
35381 Self::TIMESYNC(inner) => Some(inner.target_component),
35382 Self::COMMAND_CANCEL(inner) => Some(inner.target_component),
35383 Self::OPEN_DRONE_ID_BASIC_ID(inner) => Some(inner.target_component),
35384 Self::CANFD_FRAME(inner) => Some(inner.target_component),
35385 Self::PLAY_TUNE(inner) => Some(inner.target_component),
35386 Self::OPEN_DRONE_ID_SELF_ID(inner) => Some(inner.target_component),
35387 Self::OPEN_DRONE_ID_OPERATOR_ID(inner) => Some(inner.target_component),
35388 Self::OPEN_DRONE_ID_MESSAGE_PACK(inner) => Some(inner.target_component),
35389 Self::COMMAND_LONG(inner) => Some(inner.target_component),
35390 Self::CAN_FILTER_MODIFY(inner) => Some(inner.target_component),
35391 Self::SUPPORTED_TUNES(inner) => Some(inner.target_component),
35392 Self::PARAM_EXT_SET(inner) => Some(inner.target_component),
35393 Self::REQUEST_EVENT(inner) => Some(inner.target_component),
35394 Self::PARAM_MAP_RC(inner) => Some(inner.target_component),
35395 Self::GPS_INJECT_DATA(inner) => Some(inner.target_component),
35396 Self::MISSION_ITEM_INT(inner) => Some(inner.target_component),
35397 Self::PLAY_TUNE_V2(inner) => Some(inner.target_component),
35398 Self::MISSION_CLEAR_ALL(inner) => Some(inner.target_component),
35399 Self::MISSION_SET_CURRENT(inner) => Some(inner.target_component),
35400 Self::REQUEST_DATA_STREAM(inner) => Some(inner.target_component),
35401 Self::SERIAL_CONTROL(inner) => Some(inner.target_component),
35402 Self::COMMAND_INT(inner) => Some(inner.target_component),
35403 Self::GIMBAL_MANAGER_SET_ATTITUDE(inner) => Some(inner.target_component),
35404 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(inner) => Some(inner.target_component),
35405 Self::PARAM_REQUEST_READ(inner) => Some(inner.target_component),
35406 Self::SETUP_SIGNING(inner) => Some(inner.target_component),
35407 Self::LOG_REQUEST_DATA(inner) => Some(inner.target_component),
35408 Self::SET_POSITION_TARGET_GLOBAL_INT(inner) => Some(inner.target_component),
35409 Self::RESPONSE_EVENT_ERROR(inner) => Some(inner.target_component),
35410 Self::CAN_FRAME(inner) => Some(inner.target_component),
35411 Self::GIMBAL_MANAGER_SET_PITCHYAW(inner) => Some(inner.target_component),
35412 Self::RC_CHANNELS_OVERRIDE(inner) => Some(inner.target_component),
35413 Self::PING(inner) => Some(inner.target_component),
35414 Self::SET_ATTITUDE_TARGET(inner) => Some(inner.target_component),
35415 Self::MISSION_REQUEST_INT(inner) => Some(inner.target_component),
35416 Self::SET_POSITION_TARGET_LOCAL_NED(inner) => Some(inner.target_component),
35417 Self::PARAM_EXT_REQUEST_LIST(inner) => Some(inner.target_component),
35418 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(inner) => Some(inner.target_component),
35419 Self::PARAM_SET(inner) => Some(inner.target_component),
35420 Self::MISSION_REQUEST(inner) => Some(inner.target_component),
35421 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(inner) => Some(inner.target_component),
35422 Self::TUNNEL(inner) => Some(inner.target_component),
35423 Self::COMMAND_ACK(inner) => Some(inner.target_component),
35424 Self::MISSION_ITEM(inner) => Some(inner.target_component),
35425 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(inner) => Some(inner.target_component),
35426 Self::OPEN_DRONE_ID_AUTHENTICATION(inner) => Some(inner.target_component),
35427 Self::PARAM_REQUEST_LIST(inner) => Some(inner.target_component),
35428 _ => None,
35429 }
35430 }
35431}